From df5e2291611b3ca40c5c8da4d479150162b68208 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Tue, 1 Nov 2022 22:37:40 +0100 Subject: [PATCH 01/14] Initial layout. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/vrx_gz/CMakeLists.txt b/vrx_gz/CMakeLists.txt index 2ba453a29..98aad7852 100644 --- a/vrx_gz/CMakeLists.txt +++ b/vrx_gz/CMakeLists.txt @@ -102,6 +102,7 @@ list(APPEND VRX_GZ_PLUGINS LightBuoyPlugin PerceptionScoringPlugin NavigationScoringPlugin + ScanDockScoringPlugin SimpleHydrodynamics StationkeepingScoringPlugin Surface From 25f231860709ec7a84da93b1f75010013994b06b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 4 Nov 2022 23:21:41 +0100 Subject: [PATCH 02/14] Part 1. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/src/ScanDockScoringPlugin.cc | 321 +++++++++++++++++++++++ vrx_gz/src/ScanDockScoringPlugin.hh | 201 ++++++++++++++ vrx_gz/src/vrx_gz/bridges.py | 24 +- vrx_gz/src/vrx_gz/launch.py | 8 + vrx_gz/worlds/scan_dock_deliver_task.sdf | 18 ++ 5 files changed, 556 insertions(+), 16 deletions(-) create mode 100644 vrx_gz/src/ScanDockScoringPlugin.cc create mode 100644 vrx_gz/src/ScanDockScoringPlugin.hh diff --git a/vrx_gz/src/ScanDockScoringPlugin.cc b/vrx_gz/src/ScanDockScoringPlugin.cc new file mode 100644 index 000000000..e4dd3ce49 --- /dev/null +++ b/vrx_gz/src/ScanDockScoringPlugin.cc @@ -0,0 +1,321 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ScanDockScoringPlugin.hh" + +using namespace gz; +using namespace vrx; + +/// \brief A class to monitor if the color sequence reported matches the color +/// displayed in the light buoy. +class ColorSequenceChecker +{ + /// \brief Constructor. + /// \param[in] _expectedColors The sequence of expected colors. + /// \param[in] _colorSequenceTopic The topic used to receive the color + /// submisison. + public: ColorSequenceChecker(const std::vector &_expectedColors, + const std::string &_colorSequenceTopic); + /// \brief Enable submissions. + public: void Enable(); + + /// \brief Disable submissions. + public: void Disable(); + + /// \brief Whether a team submitted the color sequence or not. + /// \return True when the submission was received or false otherwise. + public: bool SubmissionReceived() const; + + /// \brief Wheter a team submitted the color sequence and is correct or not. + /// \return True when the team submitted the color sequence and it is correct + /// or false otherwise. + public: bool Correct() const; + + /// \brief Callback executed when a new color submission is received. + /// \param[in] _sequence Contains the submission. + private: void OnColorSequence(const msgs::StringMsg_V &_sequence); + + /// \brief The expected color sequence. + private: std::vector expectedSequence; + + /// \brief Topic where the color sequence should be sent. + private: std::string colorSequenceTopic; + + /// \brief ROS Node handle. + private: transport::Node node; + + /// \brief Whether the color sequence has been received or not. + private: bool colorSequenceReceived = false; + + /// \brief Whether the color sequence received is correct or not. + private: bool correctSequence = false; +}; + +////////////////////////////////////////////////// +ColorSequenceChecker::ColorSequenceChecker( + const std::vector &_expectedColors, + const std::string &_colorSequenceTopic) + : expectedSequence(_expectedColors), + colorSequenceTopic(_colorSequenceTopic) +{ +} + +////////////////////////////////////////////////// +void ColorSequenceChecker::Enable() +{ + this->node.Subscribe(this->colorSequenceTopic, + &ColorSequenceChecker::OnColorSequence, this); +} + +////////////////////////////////////////////////// +void ColorSequenceChecker::Disable() +{ + this->node.Unsubscribe(this->colorSequenceTopic); +} + +///////////////////////////////////////////////// +bool ColorSequenceChecker::SubmissionReceived() const +{ + return this->colorSequenceReceived; +} + +///////////////////////////////////////////////// +bool ColorSequenceChecker::Correct() const +{ + return this->correctSequence; +} + +///////////////////////////////////////////////// +void ColorSequenceChecker::OnColorSequence(const msgs::StringMsg_V &_sequence) +{ + gzmsg << "ColorSequenceChecker: Color sequence submission received:" + << _sequence.DebugString() << std::endl; + + // Sanity check: Only one submission is allowed. + if (this->colorSequenceReceived) + { + gzerr << "The color sequence has already been submitted" << std::endl; + return; + } + + // Sanity check: We should receive three colors. + if (_sequence.data_size() < 3u) + { + gzerr << "Received a color sequence with " << _sequence.data_size() + << " values but expecting three instead. Submission ignored." + << std::endl; + return; + } + + this->colorSequenceReceived = true; + + std::string color1 = _sequence.data(1); + std::string color2 = _sequence.data(2); + std::string color3 = _sequence.data(3); + + std::transform(color1.begin(), color1.end(), color1.begin(), ::tolower); + std::transform(color2.begin(), color2.end(), color2.begin(), ::tolower); + std::transform(color3.begin(), color3.end(), color3.begin(), ::tolower); + + this->correctSequence = + color1 == this->expectedSequence[0] && + color2 == this->expectedSequence[1] && + color3 == this->expectedSequence[2]; + + if (this->correctSequence) + { + gzmsg << "ColorSequenceChecker: Received color sequence is correct. " + << " Additional points will be scored." << std::endl; + } + else + { + gzmsg << "ColorSequenceChecker: Received color sequence is not correct. " + << "No additional points." << std::endl; + } +} + +/// \brief Private ScanDockScoringPlugin data class. +class ScanDockScoringPlugin::Implementation +{ + /// \brief Parse all SDF parameters. + /// \param[in] _sdf SDF elements. + /// \return True when all params were successfully parsed or false otherwise. + public: bool ParseSDF(sdf::ElementPtr _sdf); + + /// \brief In charge of receiving the team submission and compare it with + /// the color sequence from the light buoy. + public: std::unique_ptr colorChecker; + + /// \brief To check colors or not. + public: bool enableColorChecker = true; + + /// \brief Whether we have processed the color sequence submission or not. + public: bool colorSubmissionProcessed = false; + + /// \brief Points granted when the color sequence is correct. + public: double colorBonusPoints = 10.0; + + /// \brief Expected color sequence. + public: std::vector expectedSequence; + + /// \brief A mutex. + private: std::mutex mutex; +}; + +////////////////////////////////////////////////// +bool ScanDockScoringPlugin::Implementation::ParseSDF(sdf::ElementPtr _sdf) +{ + // Enable color checker - default is true + this->enableColorChecker = true; + if (_sdf->HasElement("enable_color_checker")) + this->enableColorChecker = _sdf->Get("enable_color_checker"); + + // Optional: Color sequence topic. + std::string colorSequenceTopic = "/vrx/scan_dock/color_sequence"; + if (_sdf->HasElement("color_sequence_topic")) + colorSequenceTopic = _sdf->Get("color_sequence_topic"); + + // Required: The expected color pattern. + for (auto colorIndex : {"color_1", "color_2", "color_3"}) + { + if (!_sdf->HasElement(colorIndex)) + { + gzerr << "ScanDockScoringPlugin: Missing <" << colorIndex << ">" + << std::endl; + return false; + } + + auto color = _sdf->Get(colorIndex); + std::transform(color.begin(), color.end(), color.begin(), ::tolower); + + // Sanity check: color should be red, green, blue or yellow. + if (color != "red" && color != "green" && + color != "blue" && color != "yellow") + { + gzerr << "ScanDockScoringPlugin:: Invalid color [" << color << "]" + << std::endl; + return false; + } + + this->expectedSequence.push_back(color); + } + + // Optional: the points granted when reported the correct color sequence. + if (_sdf->HasElement("color_bonus_points")) + this->colorBonusPoints = _sdf->Get("color_bonus_points"); + + // Instantiate the color checker. + if (this->enableColorChecker) + { + this->colorChecker.reset( + new ColorSequenceChecker(this->expectedSequence, colorSequenceTopic)); + } + + return true; +} + +////////////////////////////////////////////////// +ScanDockScoringPlugin::ScanDockScoringPlugin() + : ScoringPlugin(), + dataPtr(utils::MakeUniqueImpl()) +{ +} + +////////////////////////////////////////////////// +void ScanDockScoringPlugin::Configure(const sim::Entity &_entity, + const std::shared_ptr &_sdf, + sim::EntityComponentManager &_ecm, sim::EventManager &_eventMgr) +{ + ScoringPlugin::Configure(_entity, _sdf, _ecm, _eventMgr); + + auto sdf = _sdf->Clone(); + if (!this->dataPtr->ParseSDF(sdf)) + { + gzerr << "Error parsing SDF, plugin disabled." << std::endl; + return; + } +} + +////////////////////////////////////////////////// +void ScanDockScoringPlugin::PreUpdate(const sim::UpdateInfo &_info, + sim::EntityComponentManager &_ecm) +{ + if (_info.paused) + return; + + ScoringPlugin::PreUpdate(_info, _ecm); + + if (this->dataPtr->enableColorChecker) + { + // Verify the color checker. + if (!this->dataPtr->colorSubmissionProcessed && + this->dataPtr->colorChecker->SubmissionReceived()) + { + // We need to decide if we grant extra points. + if (this->dataPtr->colorChecker->Correct()) + { + gzmsg << "Adding <" << this->dataPtr->colorBonusPoints + << "> points for correct reporting of color sequence" + << std::endl; + this->SetScore(this->Score() + this->dataPtr->colorBonusPoints); + } + + // We only allow one color sequence submission. + this->dataPtr->colorChecker->Disable(); + this->dataPtr->colorSubmissionProcessed = true; + } + } +} + +////////////////////////////////////////////////// +void ScanDockScoringPlugin::OnReady() +{ +} + +////////////////////////////////////////////////// +void ScanDockScoringPlugin::OnRunning() +{ + if (this->dataPtr->enableColorChecker) + this->dataPtr->colorChecker->Enable(); +} + +GZ_ADD_PLUGIN(ScanDockScoringPlugin, + sim::System, + ScanDockScoringPlugin::ISystemConfigure, + ScanDockScoringPlugin::ISystemPreUpdate) + +GZ_ADD_PLUGIN_ALIAS(vrx::ScanDockScoringPlugin, + "vrx::ScanDockScoringPlugin") diff --git a/vrx_gz/src/ScanDockScoringPlugin.hh b/vrx_gz/src/ScanDockScoringPlugin.hh new file mode 100644 index 000000000..cf745e118 --- /dev/null +++ b/vrx_gz/src/ScanDockScoringPlugin.hh @@ -0,0 +1,201 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef VRX_SCANDOCK_SCORING_PLUGIN_HH_ +#define VRX_SCANDOCK_SCORING_PLUGIN_HH_ + +#include +#include +#include +#include +#include + +#include "ScoringPlugin.hh" + +namespace vrx +{ + /// \brief A plugin for computing the score of the scan, dock, deliver task. + /// This plugin derives from the generic ScoringPlugin class. Check out that + /// plugin for other required SDF elements. + /// This plugin requires the following SDF parameters: + /// + /// : Optional parameter to turn off color checker + /// service - default is true. + /// : Optional parameter with the ROS namespace. + /// : Optional paramter with the ROS service used to + /// receive the color submission. + /// : Optional gazebo topic used to publish the color sequence + /// defaults to /vrx/light_buoy/new_pattern + /// : Expected first color of the sequence (RED, GREEN, BLUE, YELLOW). + /// : Expected second color of the sequence (RED, GREEN, BLUE, YELLOW). + /// : Expected third color of the sequence (RED, GREEN, BLUE, YELLOW). + /// : Points granted when the color sequence is correct. + /// Default value is 10. + /// : Contains at least one of the following blocks: + /// : A bay represents a potential play where a vehicle can dock. It has + /// the following required elements: + /// The name of the bay. This is used for debugging only. + /// The gazebo topic used to receive + /// notifications from the internal activation zone. + /// The gazebo topic used to receive + /// notifications from the external activation zone. + /// Minimum amount of seconds to stay docked to be + /// considered a fully successfull dock. + /// Whether is allowed to dock in this bay or not. + /// : Points granted when the vehicle successfully + /// dock-and-undock in any bay. + /// Default value is 10. + /// : Points granted when the vehicle successfully + /// dock-and-undock in the specified bay. + /// Default value is 10. + /// : Required string with format _, where + /// color can be "red", "green", "blue", "yellow" and color can be "triangle", + /// "circle", "cross", "rectangle". If this parameter is present, a ROS message + /// will be sent in OnReady(). The vehicle should dock in the bay matching this + /// color and shape. + /// : Contains at least one of the following blocks: + /// : A shooting target. It has the following elements: + /// : The name of the topic where the "libContainPlugin" publishes + /// information for this target. + /// : The points awarded for hitting this target. + /// + /// Here's an example: + /// + /// + /// wamv + /// scan_dock_deliver + /// 3 + /// 3 + /// 300 + /// + /// + /// wamv_external_pivot_joint + /// + /// + /// wamv_external_riser + /// + /// + /// + /// + /// vrx + /// scan_dock/color_sequence + /// blue + /// green + /// red + /// + /// + /// + /// + /// bay1 + /// /vrx/dock_2022/bay_1/contain + /// + /// /vrx/dock_2022/bay_1_external/contain + /// + /// /vrx/dock_2022_placard1/symbol + /// 10.0 + /// false + /// red_circle + /// + + /// + /// bay2 + /// /vrx/dock_2022/bay_2/contain + /// + /// /vrx/dock_2022/bay_2_external/contain + /// + /// /vrx/dock_2022_placard2/symbol + /// 10.0 + /// true + /// blue_circle + /// + + /// + /// bay3 + /// /vrx/dock_2022/bay_3/contain + /// + /// /vrx/dock_2022/bay_3_external/contain + /// + /// /vrx/dock_2022_placard3/symbol + /// 10.0 + /// true + /// yellow_rectangle + /// + /// + /// + /// + /// + /// + /// + /// vrx/dock_2022_placard1_big_hole/contain + /// 5 + /// + /// + /// vrx/dock_2022_placard1_small_hole/contain + /// 10 + /// + + /// + /// + /// vrx/dock_2022_placard2_big_hole/contain + /// 5 + /// + /// + /// vrx/dock_2022_placard2_small_hole/contain + /// 10 + /// + + /// + /// + /// vrx/dock_2022_placard3_big_hole/contain + /// 5 + /// + /// + /// vrx/dock_2022_placard3_small_hole/contain + /// 10 + /// + /// + /// + class ScanDockScoringPlugin : public ScoringPlugin + { + /// \brief Constructor. + public: ScanDockScoringPlugin(); + + /// \brief Destructor. + public: ~ScanDockScoringPlugin() override = default; + + // Documentation inherited. + public: void Configure(const gz::sim::Entity &_entity, + const std::shared_ptr &_sdf, + gz::sim::EntityComponentManager &_ecm, + gz::sim::EventManager &_eventMgr) override; + + // Documentation inherited. + public: void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) override; + + // Documentation inherited. + private: void OnReady() override; + + // Documentation inherited. + private: void OnRunning() override; + + /// \brief Private data pointer. + GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr) + }; +} +#endif diff --git a/vrx_gz/src/vrx_gz/bridges.py b/vrx_gz/src/vrx_gz/bridges.py index e3d79043a..825a5d590 100644 --- a/vrx_gz/src/vrx_gz/bridges.py +++ b/vrx_gz/src/vrx_gz/bridges.py @@ -4,7 +4,6 @@ def prefix(world_name, model_name, link_name): return f'/world/{world_name}/model/{model_name}/link/{link_name}/sensor' - def imu(world_name, model_name, link_name='base_link'): sensor_prefix = prefix(world_name, model_name, link_name) return Bridge( @@ -14,7 +13,6 @@ def imu(world_name, model_name, link_name='base_link'): ros_type='sensor_msgs/msg/Imu', direction=BridgeDirection.GZ_TO_ROS) - def magnetometer(world_name, model_name, link_name='base_link'): sensor_prefix = prefix(world_name, model_name, link_name) return Bridge( @@ -24,7 +22,6 @@ def magnetometer(world_name, model_name, link_name='base_link'): ros_type='sensor_msgs/msg/MagneticField', direction=BridgeDirection.GZ_TO_ROS) - def air_pressure(world_name, model_name, link_name='base_link'): sensor_prefix = prefix(world_name, model_name, link_name) return Bridge( @@ -42,7 +39,6 @@ def pose(model_name): ros_type='tf2_msgs/msg/TFMessage', direction=BridgeDirection.GZ_TO_ROS) - def pose_static(model_name): return Bridge( gz_topic=f'/model/{model_name}/pose_static', @@ -51,7 +47,6 @@ def pose_static(model_name): ros_type='tf2_msgs/msg/TFMessage', direction=BridgeDirection.GZ_TO_ROS) - def cmd_vel(model_name): return Bridge( gz_topic=f'/model/{model_name}/cmd_vel', @@ -68,7 +63,6 @@ def thrust(model_name, side): ros_type='std_msgs/msg/Float64', direction=BridgeDirection.ROS_TO_GZ) - def thrust_joint_pos(model_name, side): # ROS naming policy indicates that first character of a name must be an alpha # character. In the case below, the gz topic has the joint index 0 as the @@ -107,7 +101,6 @@ def comms_tx(model_name): ros_type='ros_gz_interfaces/msg/Dataframe', direction=BridgeDirection.ROS_TO_GZ) - def comms_rx(model_name): return Bridge( gz_topic=f'/model/{model_name}/rx', @@ -116,7 +109,6 @@ def comms_rx(model_name): ros_type='ros_gz_interfaces/msg/Dataframe', direction=BridgeDirection.GZ_TO_ROS) - def clock(): return Bridge( gz_topic='/clock', @@ -125,7 +117,6 @@ def clock(): ros_type='rosgraph_msgs/msg/Clock', direction=BridgeDirection.GZ_TO_ROS) - def task_info(): return Bridge( gz_topic=f'/vrx/task/info', @@ -134,7 +125,6 @@ def task_info(): ros_type='ros_gz_interfaces/msg/ParamVec', direction=BridgeDirection.GZ_TO_ROS) - def contacts(): return Bridge( gz_topic=f'/vrx/contacts', @@ -143,7 +133,6 @@ def contacts(): ros_type='ros_gz_interfaces/msg/Contacts', direction=BridgeDirection.GZ_TO_ROS) - def stationkeeping_goal(): return Bridge( gz_topic=f'/vrx/stationkeeping/goal', @@ -152,7 +141,6 @@ def stationkeeping_goal(): ros_type='geometry_msgs/msg/PoseStamped', direction=BridgeDirection.GZ_TO_ROS) - def stationkeeping_mean_pose_error(): return Bridge( gz_topic=f'/vrx/stationkeeping/mean_pose_error', @@ -161,7 +149,6 @@ def stationkeeping_mean_pose_error(): ros_type='std_msgs/msg/Float32', direction=BridgeDirection.GZ_TO_ROS) - def stationkeeping_pose_error(): return Bridge( gz_topic=f'/vrx/stationkeeping/pose_error', @@ -170,7 +157,6 @@ def stationkeeping_pose_error(): ros_type='std_msgs/msg/Float32', direction=BridgeDirection.GZ_TO_ROS) - def wayfinding_waypoints(): return Bridge( gz_topic=f'/vrx/wayfinding/waypoints', @@ -179,7 +165,6 @@ def wayfinding_waypoints(): ros_type='geometry_msgs/msg/PoseArray', direction=BridgeDirection.GZ_TO_ROS) - def wayfinding_mean_error(): return Bridge( gz_topic=f'/vrx/wayfinding/mean_error', @@ -188,7 +173,6 @@ def wayfinding_mean_error(): ros_type='std_msgs/msg/Float32', direction=BridgeDirection.GZ_TO_ROS) - def wayfinding_min_errors(): return Bridge( gz_topic=f'/vrx/wayfinding/min_errors', @@ -204,3 +188,11 @@ def perception_reports(): gz_type='ignition.msgs.Pose', ros_type='geometry_msgs/msg/PoseStamped', direction=BridgeDirection.ROS_TO_GZ) + +def color_sequence_reports(): + return Bridge( + gz_topic=f'/vrx/scan_dock_deliver/color_sequence', + ros_topic=f'/vrx/scan_dock_deliver/color_sequence', + gz_type='ignition.msgs.StringMsg_V', + ros_type='ros_gz_interfaces/msg/StringVec', + direction=BridgeDirection.ROS_TO_GZ) diff --git a/vrx_gz/src/vrx_gz/launch.py b/vrx_gz/src/vrx_gz/launch.py index 8dea81c7d..08ad21600 100644 --- a/vrx_gz/src/vrx_gz/launch.py +++ b/vrx_gz/src/vrx_gz/launch.py @@ -50,6 +50,10 @@ 'wildlife_task' ] +SCAN_DOCK_DELIVER_WORLDS = [ + 'scan_dock_deliver_task' +] + def simulation(world_name, headless=False): gz_args = ['-v 4', '-r'] if headless: @@ -112,6 +116,10 @@ def competition_bridges(world_name): elif world_name in WILDLIFE_WORLDS: task_bridges = [ ] + elif world_name in SCAN_DOCK_DELIVER_WORLDS: + task_bridges = [ + vrx_gz.bridges.color_sequence_reports(), + ] bridges.extend(task_bridges) nodes = [] diff --git a/vrx_gz/worlds/scan_dock_deliver_task.sdf b/vrx_gz/worlds/scan_dock_deliver_task.sdf index 15cccbbc4..752524a7a 100644 --- a/vrx_gz/worlds/scan_dock_deliver_task.sdf +++ b/vrx_gz/worlds/scan_dock_deliver_task.sdf @@ -491,5 +491,23 @@ + + + wamv + scan_dock_deliver + /vrx/task/info + 10 + 10 + 300 + /vrx/release + + /vrx/scan_dock_deliver/color_sequence + red + green + yellow + + From f942599bfef24c411f1f6d1412e1a60dc30ce384 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 9 Nov 2022 22:32:38 +0100 Subject: [PATCH 03/14] Tweaks MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/src/ScanDockScoringPlugin.cc | 8 +++++--- vrx_gz/worlds/scan_dock_deliver_task.sdf | 2 +- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/vrx_gz/src/ScanDockScoringPlugin.cc b/vrx_gz/src/ScanDockScoringPlugin.cc index e4dd3ce49..e4231e01a 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.cc +++ b/vrx_gz/src/ScanDockScoringPlugin.cc @@ -123,6 +123,7 @@ void ColorSequenceChecker::OnColorSequence(const msgs::StringMsg_V &_sequence) { gzmsg << "ColorSequenceChecker: Color sequence submission received:" << _sequence.DebugString() << std::endl; + std::cout << std::flush; // Sanity check: Only one submission is allowed. if (this->colorSequenceReceived) @@ -142,9 +143,9 @@ void ColorSequenceChecker::OnColorSequence(const msgs::StringMsg_V &_sequence) this->colorSequenceReceived = true; - std::string color1 = _sequence.data(1); - std::string color2 = _sequence.data(2); - std::string color3 = _sequence.data(3); + std::string color1 = _sequence.data(0); + std::string color2 = _sequence.data(1); + std::string color3 = _sequence.data(2); std::transform(color1.begin(), color1.end(), color1.begin(), ::tolower); std::transform(color2.begin(), color2.end(), color2.begin(), ::tolower); @@ -165,6 +166,7 @@ void ColorSequenceChecker::OnColorSequence(const msgs::StringMsg_V &_sequence) gzmsg << "ColorSequenceChecker: Received color sequence is not correct. " << "No additional points." << std::endl; } + std::cout << std::flush; } /// \brief Private ScanDockScoringPlugin data class. diff --git a/vrx_gz/worlds/scan_dock_deliver_task.sdf b/vrx_gz/worlds/scan_dock_deliver_task.sdf index 752524a7a..8ba344942 100644 --- a/vrx_gz/worlds/scan_dock_deliver_task.sdf +++ b/vrx_gz/worlds/scan_dock_deliver_task.sdf @@ -506,7 +506,7 @@ /vrx/scan_dock_deliver/color_sequence red green - yellow + blue From 2c2645b1dcb0eade730719bae74fb49ad55f06ea Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 9 Nov 2022 22:44:01 +0100 Subject: [PATCH 04/14] Tweak MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/src/ScanDockScoringPlugin.cc | 20 +--- vrx_gz/src/ScanDockScoringPlugin.hh | 138 +++------------------------- 2 files changed, 16 insertions(+), 142 deletions(-) diff --git a/vrx_gz/src/ScanDockScoringPlugin.cc b/vrx_gz/src/ScanDockScoringPlugin.cc index e4231e01a..6de7fdb75 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.cc +++ b/vrx_gz/src/ScanDockScoringPlugin.cc @@ -20,16 +20,8 @@ #include #include #include -#include -#include -#include -#include -#include -#include #include -#include #include -#include #include #include #include @@ -59,13 +51,14 @@ class ColorSequenceChecker /// \return True when the submission was received or false otherwise. public: bool SubmissionReceived() const; - /// \brief Wheter a team submitted the color sequence and is correct or not. + /// \brief Whether a team submitted the color sequence and is correct or not. /// \return True when the team submitted the color sequence and it is correct /// or false otherwise. public: bool Correct() const; /// \brief Callback executed when a new color submission is received. - /// \param[in] _sequence Contains the submission. + /// \param[in] _sequence Contains the submission. The size of the vector + /// should be three. private: void OnColorSequence(const msgs::StringMsg_V &_sequence); /// \brief The expected color sequence. @@ -74,7 +67,7 @@ class ColorSequenceChecker /// \brief Topic where the color sequence should be sent. private: std::string colorSequenceTopic; - /// \brief ROS Node handle. + /// \brief The transport node. private: transport::Node node; /// \brief Whether the color sequence has been received or not. @@ -302,11 +295,6 @@ void ScanDockScoringPlugin::PreUpdate(const sim::UpdateInfo &_info, } } -////////////////////////////////////////////////// -void ScanDockScoringPlugin::OnReady() -{ -} - ////////////////////////////////////////////////// void ScanDockScoringPlugin::OnRunning() { diff --git a/vrx_gz/src/ScanDockScoringPlugin.hh b/vrx_gz/src/ScanDockScoringPlugin.hh index cf745e118..52bf24914 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.hh +++ b/vrx_gz/src/ScanDockScoringPlugin.hh @@ -34,141 +34,30 @@ namespace vrx /// This plugin requires the following SDF parameters: /// /// : Optional parameter to turn off color checker - /// service - default is true. - /// : Optional parameter with the ROS namespace. - /// : Optional paramter with the ROS service used to - /// receive the color submission. - /// : Optional gazebo topic used to publish the color sequence - /// defaults to /vrx/light_buoy/new_pattern - /// : Expected first color of the sequence (RED, GREEN, BLUE, YELLOW). - /// : Expected second color of the sequence (RED, GREEN, BLUE, YELLOW). - /// : Expected third color of the sequence (RED, GREEN, BLUE, YELLOW). + /// service. Default is true. + /// : Optional parameter with the topic used to + /// receive the color submission. Default is "/vrx/scan_dock/color_sequence". + /// : Expected 1st color of the sequence (RED, GREEN, BLUE, YELLOW). + /// : Expected 2nd color of the sequence (RED, GREEN, BLUE, YELLOW). + /// : Expected 3rd color of the sequence (RED, GREEN, BLUE, YELLOW). /// : Points granted when the color sequence is correct. /// Default value is 10. - /// : Contains at least one of the following blocks: - /// : A bay represents a potential play where a vehicle can dock. It has - /// the following required elements: - /// The name of the bay. This is used for debugging only. - /// The gazebo topic used to receive - /// notifications from the internal activation zone. - /// The gazebo topic used to receive - /// notifications from the external activation zone. - /// Minimum amount of seconds to stay docked to be - /// considered a fully successfull dock. - /// Whether is allowed to dock in this bay or not. - /// : Points granted when the vehicle successfully - /// dock-and-undock in any bay. - /// Default value is 10. - /// : Points granted when the vehicle successfully - /// dock-and-undock in the specified bay. - /// Default value is 10. - /// : Required string with format _, where - /// color can be "red", "green", "blue", "yellow" and color can be "triangle", - /// "circle", "cross", "rectangle". If this parameter is present, a ROS message - /// will be sent in OnReady(). The vehicle should dock in the bay matching this - /// color and shape. - /// : Contains at least one of the following blocks: - /// : A shooting target. It has the following elements: - /// : The name of the topic where the "libContainPlugin" publishes - /// information for this target. - /// : The points awarded for hitting this target. - /// /// Here's an example: - /// + /// /// /// wamv /// scan_dock_deliver /// 3 /// 3 /// 300 - /// - /// - /// wamv_external_pivot_joint - /// - /// - /// wamv_external_riser - /// - /// + /// /vrx/release /// /// - /// vrx - /// scan_dock/color_sequence - /// blue + /// /vrx/scan_dock_deliver/color_sequence + /// red /// green - /// red - /// - /// - /// - /// - /// bay1 - /// /vrx/dock_2022/bay_1/contain - /// - /// /vrx/dock_2022/bay_1_external/contain - /// - /// /vrx/dock_2022_placard1/symbol - /// 10.0 - /// false - /// red_circle - /// - - /// - /// bay2 - /// /vrx/dock_2022/bay_2/contain - /// - /// /vrx/dock_2022/bay_2_external/contain - /// - /// /vrx/dock_2022_placard2/symbol - /// 10.0 - /// true - /// blue_circle - /// - - /// - /// bay3 - /// /vrx/dock_2022/bay_3/contain - /// - /// /vrx/dock_2022/bay_3_external/contain - /// - /// /vrx/dock_2022_placard3/symbol - /// 10.0 - /// true - /// yellow_rectangle - /// - /// - /// - /// - /// - /// - /// - /// vrx/dock_2022_placard1_big_hole/contain - /// 5 - /// - /// - /// vrx/dock_2022_placard1_small_hole/contain - /// 10 - /// - - /// - /// - /// vrx/dock_2022_placard2_big_hole/contain - /// 5 - /// - /// - /// vrx/dock_2022_placard2_small_hole/contain - /// 10 - /// - - /// - /// - /// vrx/dock_2022_placard3_big_hole/contain - /// 5 - /// - /// - /// vrx/dock_2022_placard3_small_hole/contain - /// 10 - /// - /// + /// blue /// class ScanDockScoringPlugin : public ScoringPlugin { @@ -188,9 +77,6 @@ namespace vrx public: void PreUpdate(const gz::sim::UpdateInfo &_info, gz::sim::EntityComponentManager &_ecm) override; - // Documentation inherited. - private: void OnReady() override; - // Documentation inherited. private: void OnRunning() override; From e54e92d837c075698453bf791dcef970f8107603 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 9 Nov 2022 23:08:43 +0100 Subject: [PATCH 05/14] Remove unused bridges. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/src/vrx_gz/bridges.py | 17 ----------------- vrx_gz/src/vrx_gz/launch.py | 1 - 2 files changed, 18 deletions(-) diff --git a/vrx_gz/src/vrx_gz/bridges.py b/vrx_gz/src/vrx_gz/bridges.py index 825a5d590..f99c74990 100644 --- a/vrx_gz/src/vrx_gz/bridges.py +++ b/vrx_gz/src/vrx_gz/bridges.py @@ -4,15 +4,6 @@ def prefix(world_name, model_name, link_name): return f'/world/{world_name}/model/{model_name}/link/{link_name}/sensor' -def imu(world_name, model_name, link_name='base_link'): - sensor_prefix = prefix(world_name, model_name, link_name) - return Bridge( - gz_topic=f'{sensor_prefix}/imu_sensor/imu', - ros_topic='imu/data', - gz_type='ignition.msgs.IMU', - ros_type='sensor_msgs/msg/Imu', - direction=BridgeDirection.GZ_TO_ROS) - def magnetometer(world_name, model_name, link_name='base_link'): sensor_prefix = prefix(world_name, model_name, link_name) return Bridge( @@ -125,14 +116,6 @@ def task_info(): ros_type='ros_gz_interfaces/msg/ParamVec', direction=BridgeDirection.GZ_TO_ROS) -def contacts(): - return Bridge( - gz_topic=f'/vrx/contacts', - ros_topic=f'/vrx/contacts', - gz_type='ignition.msgs.Contacts', - ros_type='ros_gz_interfaces/msg/Contacts', - direction=BridgeDirection.GZ_TO_ROS) - def stationkeeping_goal(): return Bridge( gz_topic=f'/vrx/stationkeeping/goal', diff --git a/vrx_gz/src/vrx_gz/launch.py b/vrx_gz/src/vrx_gz/launch.py index 08ad21600..d848ee4b8 100644 --- a/vrx_gz/src/vrx_gz/launch.py +++ b/vrx_gz/src/vrx_gz/launch.py @@ -92,7 +92,6 @@ def simulation(world_name, headless=False): def competition_bridges(world_name): bridges = [ vrx_gz.bridges.clock(), - vrx_gz.bridges.contacts(), vrx_gz.bridges.task_info(), ] From 30b543ab8d8b618d1e85546081761bd54591d49b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 11 Nov 2022 00:23:29 +0100 Subject: [PATCH 06/14] Dock checker added. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/src/ScanDockScoringPlugin.cc | 413 +++++++++++++++++++++++++++- vrx_gz/src/ScanDockScoringPlugin.hh | 3 + 2 files changed, 415 insertions(+), 1 deletion(-) diff --git a/vrx_gz/src/ScanDockScoringPlugin.cc b/vrx_gz/src/ScanDockScoringPlugin.cc index 6de7fdb75..745b0ff5f 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.cc +++ b/vrx_gz/src/ScanDockScoringPlugin.cc @@ -15,6 +15,8 @@ * */ +#include +#include #include #include #include @@ -162,6 +164,245 @@ void ColorSequenceChecker::OnColorSequence(const msgs::StringMsg_V &_sequence) std::cout << std::flush; } +/// \brief A class to monitor if the vehicle docked in a given bay. +class DockChecker +{ + /// \brief Constructor. + /// \param[in] _name The name of the checker (only used for debugging). + /// \param[in] _internalActivationTopic The gazebo topic used to receive + /// notifications about the internal activation zone. + /// \param[in] _externalActivationTopic The gazebo topic used to receive + /// notifications about the external activation zone. + /// from the "contain" plugin. + /// \param[in] _minDockTime Minimum amount of seconds to stay docked to be + /// considered a fully successfull dock. + /// \param[in] _dockAllowed Whether is allowed to dock in this bay or not. + /// \param[in] _announceSymbol Optional symbol to announce via msgs. + /// \param[in] _symbolTopic Optional topic to announce the symbol. + public: DockChecker(const std::string &_name, + const std::string &_internalActivationTopic, + const std::string &_exteriorActivationTopic, + const std::chrono::duration _minDockTime, + const bool _dockAllowed, + const std::string &_announceSymbol, + const std::string &_symbolTopic); + + /// \brief The name of this checker. + public: std::string name; + + /// \brief Whether the robot has been successfully docked in this bay or not. + /// \return True when the robot has been docked or false otherwise. + public: bool AnytimeDocked() const; + + /// \brief Whether the robot is currently at the entrance of the bay. + /// \return True when the robot is at the entrance or false othwerwise. + public: bool AtEntrance() const; + + /// \brief Whether it is allowed to dock in this bay or not. + public: bool Allowed() const; + + /// \brief Announce the symbol of the bay. + public: void AnnounceSymbol(); + + /// \brief Update function that needs to be executed periodically. + /// \param[in] _info Update information. + public: void Update(const sim::UpdateInfo &_info); + + /// \brief Callback triggered when the vehicle enters or exits the activation + /// zone. + /// \param[in] _msg The current state (0: exiting, 1: entering). + private: void OnInternalActivationEvent(const msgs::Boolean &_msg); + + /// \brief Callback triggered when the vehicle enters or exits the activation + /// zone. + /// \param[in] _msg The current state (0: exiting, 1: entering). + private: void OnExternalActivationEvent(const msgs::Boolean &_msg); + + /// \brief The gazebo topic used to receive notifications + /// from the internal activation zone. + private: std::string internalActivationTopic; + + /// \brief The gazebo topic used to receive notifications + /// from the external activation zone. + private: std::string externalActivationTopic; + + /// \brief Minimum amount of seconds to stay docked to be + /// considered a fully successfull dock. + private: std::chrono::duration minDockTime; + + /// \brief Current simulation time. + private: std::chrono::duration simTime; + + /// \brief Whether is allowed to dock in this bay or not. + private: bool dockAllowed; + + /// \brief Timer used to calculate the elapsed time docked in the bay. + private: std::chrono::duration timer; + + /// \brief Ignition Transport node used for communication. + private: transport::Node ignNode; + + /// \brief Whether the vehicle has successfully docked or not. + private: bool anytimeDocked = false; + + /// \brief Whether the vehicle is at the entrance of the bay or not. + private: bool atEntrance = false; + + /// \brief Color and shape of symbol to announce. E.g.: red_cross, blue_circle + private: msgs::StringMsg announceSymbol; + + /// \brief Publisher for the symbol. + private: transport::Node::Publisher symbolPub; + + /// \brief Topic where the target symbol will be published. + private: std::string symbolTopic = "/vrx/scan_dock/placard_symbol"; + + /// \brief The transport node. + private: transport::Node node; + + /// \brief Publish the placard symbols. + private: transport::Node::Publisher dockPlacardPub; +}; + +///////////////////////////////////////////////// +DockChecker::DockChecker(const std::string &_name, + const std::string &_internalActivationTopic, + const std::string &_externalActivationTopic, + const std::chrono::duration _minDockTime, const bool _dockAllowed, + const std::string &_announceSymbol, const std::string &_symbolTopic) + : name(_name), + internalActivationTopic(_internalActivationTopic), + externalActivationTopic(_externalActivationTopic), + minDockTime(_minDockTime), + dockAllowed(_dockAllowed), + symbolTopic(_symbolTopic) +{ + this->timer = + std::chrono::duration(std::numeric_limits::max()); + + this->announceSymbol.set_data(_announceSymbol); + + // Subscriber to receive ContainPlugin updates. + this->node.Subscribe(this->internalActivationTopic, + &DockChecker::OnInternalActivationEvent, this); + this->node.Subscribe(this->externalActivationTopic, + &DockChecker::OnExternalActivationEvent, this); +} + +///////////////////////////////////////////////// +bool DockChecker::AnytimeDocked() const +{ + return this->anytimeDocked; +} + +///////////////////////////////////////////////// +bool DockChecker::AtEntrance() const +{ + return this->atEntrance; +} + +///////////////////////////////////////////////// +bool DockChecker::Allowed() const +{ + return this->dockAllowed; +} + +///////////////////////////////////////////////// +void DockChecker::AnnounceSymbol() +{ + // Override the docks own sdf parameters + this->dockPlacardPub = this->node.Advertise( + this->symbolTopic); + + msgs::StringMsg_V symbol; + // Add the shape. + symbol.add_data(this->announceSymbol.data().substr( + this->announceSymbol.data().find("_") + 1)); + // Add the color. + symbol.add_data(this->announceSymbol.data().substr( + 0, this->announceSymbol.data().find("_"))); + + this->dockPlacardPub.Publish(symbol); + + if (this->dockAllowed) + { + this->symbolPub = this->node.Advertise(this->symbolTopic); + this->symbolPub.Publish(this->announceSymbol); + } +} + +///////////////////////////////////////////////// +void DockChecker::Update(const sim::UpdateInfo &_info) +{ + this->simTime = _info.simTime; + + if (this->anytimeDocked) + return; + + auto elapsed = _info.simTime - this->timer; + this->anytimeDocked = elapsed >= this->minDockTime; + + if (this->anytimeDocked) + { + gzmsg << "Successfully stayed in dock for " << this->minDockTime.count() + << " seconds, transitioning to state" << std::endl; + } +} + +///////////////////////////////////////////////// +void DockChecker::OnInternalActivationEvent(const msgs::Boolean &_msg) +{ + // Currently docked. + if (_msg.data() == 1) + { + this->timer = this->simTime; + gzmsg << "Entering internal dock activation zone, transitioning to " + << " state in [" << this->name << "]." << std::endl; + } + + // Currently undocked. + if (_msg.data() == 0) + { + this->timer = + std::chrono::duration(std::numeric_limits::max()); + if (this->AnytimeDocked()) + { + gzmsg << "Leaving internal dock activation zone in [" << this->name + << "] after required time - transitioning to state." + << std::endl; + } + else + { + gzmsg << "Leaving internal dock activation zone in [" << this->name + << "] early - transitioning back to state." + << std::endl; + } + } + + gzdbg << "[" << this->name << "] OnInternalActivationEvent(): " + << _msg.data() << std::endl; +} + +///////////////////////////////////////////////// +void DockChecker::OnExternalActivationEvent(const msgs::Boolean &_msg) +{ + this->atEntrance = _msg.data() == 1; + + if (this->atEntrance) + { + gzmsg << "Entering external dock activation zone in [" << this->name + << "]" << std::endl; + } + else + { + gzmsg << "Leaving external dock activation zone in [" << this->name + << "]" << std::endl; + } + + gzdbg << "[" << this->name << "] OnExternalActivationEvent(): " + << _msg.data() << std::endl; +} + /// \brief Private ScanDockScoringPlugin data class. class ScanDockScoringPlugin::Implementation { @@ -174,6 +415,9 @@ class ScanDockScoringPlugin::Implementation /// the color sequence from the light buoy. public: std::unique_ptr colorChecker; + /// \brief Monitor all the available bays to decide when the vehicle docks. + public: std::vector> dockCheckers; + /// \brief To check colors or not. public: bool enableColorChecker = true; @@ -183,11 +427,19 @@ class ScanDockScoringPlugin::Implementation /// \brief Points granted when the color sequence is correct. public: double colorBonusPoints = 10.0; + /// \brief Points granted when the vehicle successfully + /// dock-and-undock in any bay + public: double dockBonusPoints = 10.0; + + /// \brief Points granted when the vehicle successfully + /// dock-and-undock in the specified bay. + public: double correctDockBonusPoints = 10.0; + /// \brief Expected color sequence. public: std::vector expectedSequence; /// \brief A mutex. - private: std::mutex mutex; + public: std::mutex mutex; }; ////////////////////////////////////////////////// @@ -239,6 +491,107 @@ bool ScanDockScoringPlugin::Implementation::ParseSDF(sdf::ElementPtr _sdf) new ColorSequenceChecker(this->expectedSequence, colorSequenceTopic)); } + // Required: Parse the bays. + if (!_sdf->HasElement("bays")) + { + gzerr << " missing" << std::endl; + return false; + } + + auto baysElem = _sdf->GetElement("bays"); + if (!baysElem->HasElement("bay")) + { + gzerr << " missing" << std::endl; + return false; + } + + auto bayElem = baysElem->GetElement("bay"); + while (bayElem) + { + // Required: bay name. + if (!bayElem->GetElement("name")) + { + gzerr << " missing" << std::endl; + return false; + } + std::string bayName = bayElem->Get("name"); + + // Required: internal_activation topic. + if (!bayElem->GetElement("internal_activation_topic")) + { + gzerr << " missing" << std::endl; + return false; + } + std::string internalActivationTopic = + bayElem->Get("internal_activation_topic"); + + // Required: external_activation topic. + if (!bayElem->GetElement("external_activation_topic")) + { + gzerr << " missing" << std::endl; + return false; + } + std::string externalActivationTopic = + bayElem->Get("external_activation_topic"); + + // Required: gazebo symbol topic. + if (!bayElem->GetElement("symbol_topic")) + { + gzerr << " missing" << std::endl; + return false; + } + std::string symbolTopic = bayElem->Get("symbol_topic"); + + // Required: minimum time to be considered "docked". + if (!bayElem->GetElement("min_dock_time")) + { + gzerr << " missing" << std::endl; + return false; + } + double minDockTime = bayElem->Get("min_dock_time"); + + // Required: dock allowed. + if (!bayElem->GetElement("dock_allowed")) + { + gzerr << " missing" << std::endl; + return false; + } + bool dockAllowed = bayElem->Get("dock_allowed"); + + std::string announceSymbol = ""; + if (!bayElem->HasElement("symbol")) + { + gzerr << " not found" << std::endl; + } + announceSymbol = bayElem->GetElement("symbol")->Get(); + + // Create a new dock checker. + std::unique_ptr dockChecker( + new DockChecker(bayName, internalActivationTopic, + externalActivationTopic, std::chrono::duration(minDockTime), + dockAllowed, announceSymbol, symbolTopic)); + + // Add the dock checker. + this->dockCheckers.push_back(std::move(dockChecker)); + + // Process the next checker. + bayElem = bayElem->GetNextElement(); + } + + // Optional: the points granted when the vehicle docks in any bay. + if (_sdf->HasElement("dock_bonus_points")) + { + this->dockBonusPoints = + _sdf->GetElement("dock_bonus_points")->Get(); + } + + // Optional: the points granted when the vehicle docks in the expected bay. + if (_sdf->HasElement("correct_dock_bonus_points")) + { + this->correctDockBonusPoints = + _sdf->GetElement("correct_dock_bonus_points")->Get(); + } + return true; } @@ -293,6 +646,60 @@ void ScanDockScoringPlugin::PreUpdate(const sim::UpdateInfo &_info, this->dataPtr->colorSubmissionProcessed = true; } } + + // Verify the dock checkers. + for (auto &dockChecker : this->dataPtr->dockCheckers) + { + // We always need to update the checkers. + dockChecker->Update(_info); + + // Nothing to do if nobody ever docked or we're still inside the bay. + if (!dockChecker->AnytimeDocked() || !dockChecker->AtEntrance()) + continue; + + // Points granted for docking! + this->SetScore(this->Score() + this->dataPtr->dockBonusPoints); + if (this->TaskState() == "running") + { + gzmsg << "Successfully docked in [" << dockChecker->name << "]" + << ". Awarding " << this->dataPtr->dockBonusPoints << " points." + << std::endl; + } + + // Is this the right bay? + if (dockChecker->Allowed()) + { + this->SetScore(this->Score() + this->dataPtr->correctDockBonusPoints); + if (this->TaskState() == "running") + { + gzmsg << "Docked in correct dock [" << dockChecker->name << "]" + << ". Awarding " << this->dataPtr->correctDockBonusPoints + << " more points." << std::endl; + } + } + else + { + if (this->TaskState() == "running") + { + gzmsg << "Docked in incorrect dock [" << dockChecker->name << "]" + << ". No additional points." << std::endl; + } + } + + // Time to finish the task as the vehicle docked. + // Note that we only allow to dock one time. This is to prevent teams + // docking in all possible bays. + this->Exit(); + break; + } +} + +////////////////////////////////////////////////// +void ScanDockScoringPlugin::OnReady() +{ + // Announce the symbol if needed. + for (auto &dockChecker : this->dataPtr->dockCheckers) + dockChecker->AnnounceSymbol(); } ////////////////////////////////////////////////// @@ -300,6 +707,10 @@ void ScanDockScoringPlugin::OnRunning() { if (this->dataPtr->enableColorChecker) this->dataPtr->colorChecker->Enable(); + + // Announce the symbol if needed. + for (auto &dockChecker : this->dataPtr->dockCheckers) + dockChecker->AnnounceSymbol(); } GZ_ADD_PLUGIN(ScanDockScoringPlugin, diff --git a/vrx_gz/src/ScanDockScoringPlugin.hh b/vrx_gz/src/ScanDockScoringPlugin.hh index 52bf24914..a97342d29 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.hh +++ b/vrx_gz/src/ScanDockScoringPlugin.hh @@ -77,6 +77,9 @@ namespace vrx public: void PreUpdate(const gz::sim::UpdateInfo &_info, gz::sim::EntityComponentManager &_ecm) override; + // Documentation inherited. + private: void OnReady() override; + // Documentation inherited. private: void OnRunning() override; From 73299ed2d4c4632f0f1315ebd6d1237a19450876 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 11 Nov 2022 18:27:12 +0100 Subject: [PATCH 07/14] Testing performer plugins. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/config/wamv.yaml | 4 +- vrx_gz/launch/competition.launch.py | 2 +- vrx_gz/models/dock_2022/model.sdf | 168 +++++++++++++++-------- vrx_gz/worlds/scan_dock_deliver_task.sdf | 56 ++++++++ 4 files changed, 173 insertions(+), 57 deletions(-) diff --git a/vrx_gz/config/wamv.yaml b/vrx_gz/config/wamv.yaml index c0030155a..e8ad417da 100644 --- a/vrx_gz/config/wamv.yaml +++ b/vrx_gz/config/wamv.yaml @@ -83,7 +83,7 @@ joy_teleop: axis_mappings: data: axis: 1 - scale: 1000.0 + scale: 400.0 offset: 0 right_thrust: @@ -94,7 +94,7 @@ joy_teleop: axis_mappings: data: axis: 3 - scale: 1000.0 + scale: 400.0 offset: 0 left_pos: diff --git a/vrx_gz/launch/competition.launch.py b/vrx_gz/launch/competition.launch.py index 9d13e862e..6b63520e8 100644 --- a/vrx_gz/launch/competition.launch.py +++ b/vrx_gz/launch/competition.launch.py @@ -39,7 +39,7 @@ def launch(context, *args, **kwargs): with open(config_file, 'r') as stream: models = Model.FromConfig(stream) else: - m = Model('wamv', 'wam-v', [-532, 162, 0, 0, 0, 1]) + m = Model('wamv', 'wam-v', [-492, 186, 0, 0, 0, 1.2]) if robot_urdf and robot_urdf != '': m.set_urdf(robot_urdf) models.append(m) diff --git a/vrx_gz/models/dock_2022/model.sdf b/vrx_gz/models/dock_2022/model.sdf index 1018b801d..b2d4679a6 100644 --- a/vrx_gz/models/dock_2022/model.sdf +++ b/vrx_gz/models/dock_2022/model.sdf @@ -87,10 +87,9 @@ - + 0 1 0 + 0 1 0 + 0 1 0 1 @@ -102,10 +101,9 @@ - + 0 1 0 + 0 1 0 + 0 1 0 1 --> @@ -120,14 +118,13 @@ - + + + + /vrx/dock_2022/bay_1/contains + 0 -4.5 -1.5 0 0 0 + + + 1.5 4 2 + + + + + + /vrx/dock_2022/bay_1_external/contains + 0 -9.5 -1.5 0 0 0 + + + 5.5 1.5 2 + + + @@ -236,10 +256,9 @@ - + 0 1 0 + 0 1 0 + 0 1 0 1 @@ -251,10 +270,9 @@ - + 0 1 0 + 0 1 0 + 0 1 0 1 --> @@ -269,14 +287,13 @@ - + + + + /vrx/dock_2022/bay_2/contains + 0 -4.5 -1.5 0 0 0 + + + 1.5 4 2 + + + + + + /vrx/dock_2022/bay_2_external/contains + 0 -9.5 -1.5 0 0 0 + + + 5.5 1.5 2 + + + @@ -385,10 +425,9 @@ - + 0 1 0 + 0 1 0 + 0 1 0 1 @@ -400,10 +439,9 @@ - + 0 1 0 + 0 1 0 + 0 1 0 1 --> @@ -418,14 +456,13 @@ - + + + + /vrx/dock_2022/bay_3/contains + 0 -4.5 -1.5 0 0 0 + + + 1.5 4 2 + + + + + + /vrx/dock_2022/bay_3_external/contains + 0 -9.5 -1.5 0 0 0 + + + 5.5 1.5 2 + + + diff --git a/vrx_gz/worlds/scan_dock_deliver_task.sdf b/vrx_gz/worlds/scan_dock_deliver_task.sdf index 34c03b38d..26e18c8d6 100644 --- a/vrx_gz/worlds/scan_dock_deliver_task.sdf +++ b/vrx_gz/worlds/scan_dock_deliver_task.sdf @@ -532,6 +532,19 @@ dock_2022 -480 190 0 0 0 1.0 + + + @@ -550,6 +563,49 @@ red green blue + + 15 + 5 + + + bay1 + /vrx/dock_2022/bay_1/contain + /vrx/dock_2022/bay_1_external/contain + /vrx/dock_2022_placard1/symbol + 10.0 + True + red_rectangle + + + bay2 + /vrx/dock_2022/bay_2/contain + /vrx/dock_2022/bay_2_external/contain + /vrx/dock_2022_placard2/symbol + 10.0 + False + blue_triangle + + + bay3 + /vrx/dock_2022/bay_3/contain + /vrx/dock_2022/bay_3_external/contain + /vrx/dock_2022_placard3/symbol + 10.0 + False + yellow_circle + + + + + + + wamv + + + 2 2 2 + + + From 9e689fb10ede12234d5b99ea09af92db58ee5eec Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 11 Nov 2022 22:24:52 +0100 Subject: [PATCH 08/14] Testing MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/models/wam-v/model.sdf.erb | 11 +++++++++++ vrx_gz/worlds/scan_dock_deliver_task.sdf | 2 +- 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/vrx_gz/models/wam-v/model.sdf.erb b/vrx_gz/models/wam-v/model.sdf.erb index 92ec1d445..b735b39a2 100644 --- a/vrx_gz/models/wam-v/model.sdf.erb +++ b/vrx_gz/models/wam-v/model.sdf.erb @@ -282,5 +282,16 @@ end + + + wamv + + + 4 2 2 + + + + + diff --git a/vrx_gz/worlds/scan_dock_deliver_task.sdf b/vrx_gz/worlds/scan_dock_deliver_task.sdf index 26e18c8d6..5a4fe8da0 100644 --- a/vrx_gz/worlds/scan_dock_deliver_task.sdf +++ b/vrx_gz/worlds/scan_dock_deliver_task.sdf @@ -602,7 +602,7 @@ wamv - 2 2 2 + 4 2 2 From 2b75230d52a0739aa31220368130807cb877ebf3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Thu, 17 Nov 2022 22:00:03 +0100 Subject: [PATCH 09/14] Docking working. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/models/dock_2022/model.sdf | 191 +- vrx_gz/models/wam-v/model.sdf.erb | 11 - vrx_gz/src/ScanDockScoringPlugin.cc | 143 +- vrx_gz/src/ScanDockScoringPlugin.hh | 53 + vrx_gz/worlds/scan_dock_deliver_task.sdf | 28 +- .../models/cpu_cases/mesh/cpu_cases.dae | 9610 +---------------- .../wamv_description/urdf/cpu_cases.xacro | 42 +- 7 files changed, 425 insertions(+), 9653 deletions(-) diff --git a/vrx_gz/models/dock_2022/model.sdf b/vrx_gz/models/dock_2022/model.sdf index b2d4679a6..2a10f0dbe 100644 --- a/vrx_gz/models/dock_2022/model.sdf +++ b/vrx_gz/models/dock_2022/model.sdf @@ -118,7 +118,7 @@ - + - /vrx/dock_2022/bay_1/contains @@ -174,7 +174,7 @@ 5.5 1.5 2 - + --> @@ -287,7 +287,7 @@ - + - /vrx/dock_2022/bay_2/contains @@ -331,9 +331,9 @@ 1.5 4 2 - + --> - /vrx/dock_2022/bay_2_external/contains @@ -343,7 +343,7 @@ 5.5 1.5 2 - + --> @@ -456,7 +456,7 @@ - + - /vrx/dock_2022/bay_3/contains @@ -512,10 +512,171 @@ 5.5 1.5 2 - + --> - + + + + 1.5 3 0.25 0 0 1.5707963267948966 + + 0 1 0 + 0 1 0 + 0 1 0 1 + + + + 1.5 4 2 + + + 0.0 + + + + 1.5 9 0.25 0 0 1.5707963267948966 + + 0 1 0 + 0 1 0 + 0 1 0 1 + + + + 1.5 4 2 + + + 0.0 + + + + 1.5 15 0.25 0 0 1.5707963267948966 + + 0 1 0 + 0 1 0 + 0 1 0 1 + + + + 1.5 4 2 + + + 0.0 + + + + -3.5 3 0.25 0 0 1.5707963267948966 + + 1 0 0 + 1 0 0 + 1 0 0 1 + + + + 5.5 1.5 2 + + + + + + -3.5 9 0.25 0 0 1.5707963267948966 + + 1 0 0 + 1 0 0 + 1 0 0 1 + + + + 5.5 1.5 2 + + + + + + -3.5 15 0.25 0 0 1.5707963267948966 + + 1 0 0 + 1 0 0 + 1 0 0 1 + + + + 5.5 1.5 2 + + + + + + + + /vrx/dock_2022/bay_1/contain + 1.5 3 0.25 0 0 1.5707963267948966 + + + 1.5 4 2 + + + + + + /vrx/dock_2022/bay_2/contain + 1.5 9 0.25 0 0 1.5707963267948966 + + + 1.5 4 2 + + + + + + /vrx/dock_2022/bay_3/contain + 1.5 15 0.25 0 0 1.5707963267948966 + + + 1.5 4 2 + + + + + + /vrx/dock_2022/bay_1_external/contain + -3.5 3 0.25 0 0 1.5707963267948966 + + + 5.5 1.5 2 + + + + + + /vrx/dock_2022/bay_2_external/contain + -3.5 9 0.25 0 0 1.5707963267948966 + + + 5.5 1.5 2 + + + + + + /vrx/dock_2022/bay_3_external/contain + -3.5 15 0.25 0 0 1.5707963267948966 + + + 5.5 1.5 2 + + + diff --git a/vrx_gz/models/wam-v/model.sdf.erb b/vrx_gz/models/wam-v/model.sdf.erb index b735b39a2..92ec1d445 100644 --- a/vrx_gz/models/wam-v/model.sdf.erb +++ b/vrx_gz/models/wam-v/model.sdf.erb @@ -282,16 +282,5 @@ end - - - wamv - - - 4 2 2 - - - - - diff --git a/vrx_gz/src/ScanDockScoringPlugin.cc b/vrx_gz/src/ScanDockScoringPlugin.cc index 745b0ff5f..d35c95480 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.cc +++ b/vrx_gz/src/ScanDockScoringPlugin.cc @@ -16,12 +16,15 @@ */ #include +#include #include #include #include #include #include #include +#include +#include #include #include #include @@ -177,7 +180,8 @@ class DockChecker /// \param[in] _minDockTime Minimum amount of seconds to stay docked to be /// considered a fully successfull dock. /// \param[in] _dockAllowed Whether is allowed to dock in this bay or not. - /// \param[in] _announceSymbol Optional symbol to announce via msgs. + /// \param[in] _announceSymbol Symbol to announce via msgs. + /// E.g.: red_cross, blue_circle /// \param[in] _symbolTopic Optional topic to announce the symbol. public: DockChecker(const std::string &_name, const std::string &_internalActivationTopic, @@ -211,23 +215,23 @@ class DockChecker /// \brief Callback triggered when the vehicle enters or exits the activation /// zone. /// \param[in] _msg The current state (0: exiting, 1: entering). - private: void OnInternalActivationEvent(const msgs::Boolean &_msg); + private: void OnInternalActivationEvent(const msgs::Pose &_msg); /// \brief Callback triggered when the vehicle enters or exits the activation /// zone. /// \param[in] _msg The current state (0: exiting, 1: entering). - private: void OnExternalActivationEvent(const msgs::Boolean &_msg); + private: void OnExternalActivationEvent(const msgs::Pose &_msg); - /// \brief The gazebo topic used to receive notifications - /// from the internal activation zone. + /// \brief The topic used to receive notifications from the internal + /// activation zone. private: std::string internalActivationTopic; - /// \brief The gazebo topic used to receive notifications - /// from the external activation zone. + /// \brief The topic used to receive notifications from the external + /// activation zone. private: std::string externalActivationTopic; - /// \brief Minimum amount of seconds to stay docked to be - /// considered a fully successfull dock. + /// \brief Minimum amount of seconds to stay docked to be considered a fully + /// successfull dock. private: std::chrono::duration minDockTime; /// \brief Current simulation time. @@ -239,20 +243,14 @@ class DockChecker /// \brief Timer used to calculate the elapsed time docked in the bay. private: std::chrono::duration timer; - /// \brief Ignition Transport node used for communication. - private: transport::Node ignNode; - /// \brief Whether the vehicle has successfully docked or not. private: bool anytimeDocked = false; /// \brief Whether the vehicle is at the entrance of the bay or not. private: bool atEntrance = false; - /// \brief Color and shape of symbol to announce. E.g.: red_cross, blue_circle - private: msgs::StringMsg announceSymbol; - - /// \brief Publisher for the symbol. - private: transport::Node::Publisher symbolPub; + /// \brief Shape and color of symbol to announce. E.g.: ["red", "cross"] + private: msgs::StringMsg_V symbol; /// \brief Topic where the target symbol will be published. private: std::string symbolTopic = "/vrx/scan_dock/placard_symbol"; @@ -277,16 +275,33 @@ DockChecker::DockChecker(const std::string &_name, dockAllowed(_dockAllowed), symbolTopic(_symbolTopic) { + // Override the docks own sdf parameters + this->dockPlacardPub = this->node.Advertise( + this->symbolTopic); + + // Add the shape. + this->symbol.add_data(_announceSymbol.substr(_announceSymbol.find("_") + 1)); + // Add the color. + this->symbol.add_data(_announceSymbol.substr(0, _announceSymbol.find("_"))); + this->timer = std::chrono::duration(std::numeric_limits::max()); - this->announceSymbol.set_data(_announceSymbol); - // Subscriber to receive ContainPlugin updates. - this->node.Subscribe(this->internalActivationTopic, - &DockChecker::OnInternalActivationEvent, this); - this->node.Subscribe(this->externalActivationTopic, - &DockChecker::OnExternalActivationEvent, this); + if (!this->node.Subscribe(this->internalActivationTopic, + &DockChecker::OnInternalActivationEvent, this)) + { + gzerr << "Error subscribing to topic [" << this->internalActivationTopic + << "]" << std::endl; + return; + } + if (!this->node.Subscribe(this->externalActivationTopic, + &DockChecker::OnExternalActivationEvent, this)) + { + gzerr << "Error subscribing to topic [" << this->externalActivationTopic + << "]" << std::endl; + return; + } } ///////////////////////////////////////////////// @@ -310,25 +325,7 @@ bool DockChecker::Allowed() const ///////////////////////////////////////////////// void DockChecker::AnnounceSymbol() { - // Override the docks own sdf parameters - this->dockPlacardPub = this->node.Advertise( - this->symbolTopic); - - msgs::StringMsg_V symbol; - // Add the shape. - symbol.add_data(this->announceSymbol.data().substr( - this->announceSymbol.data().find("_") + 1)); - // Add the color. - symbol.add_data(this->announceSymbol.data().substr( - 0, this->announceSymbol.data().find("_"))); - - this->dockPlacardPub.Publish(symbol); - - if (this->dockAllowed) - { - this->symbolPub = this->node.Advertise(this->symbolTopic); - this->symbolPub.Publish(this->announceSymbol); - } + this->dockPlacardPub.Publish(this->symbol); } ///////////////////////////////////////////////// @@ -350,10 +347,21 @@ void DockChecker::Update(const sim::UpdateInfo &_info) } ///////////////////////////////////////////////// -void DockChecker::OnInternalActivationEvent(const msgs::Boolean &_msg) +void DockChecker::OnInternalActivationEvent(const msgs::Pose &_msg) { + // Get the state from the header. + std::string state; + for (const auto &data : _msg.header().data()) + { + if (data.key() == "state" && !data.value().empty()) + { + state = data.value(0); + break; + } + } + // Currently docked. - if (_msg.data() == 1) + if (state == "1") { this->timer = this->simTime; gzmsg << "Entering internal dock activation zone, transitioning to " @@ -361,7 +369,7 @@ void DockChecker::OnInternalActivationEvent(const msgs::Boolean &_msg) } // Currently undocked. - if (_msg.data() == 0) + if (state == "0") { this->timer = std::chrono::duration(std::numeric_limits::max()); @@ -380,13 +388,25 @@ void DockChecker::OnInternalActivationEvent(const msgs::Boolean &_msg) } gzdbg << "[" << this->name << "] OnInternalActivationEvent(): " - << _msg.data() << std::endl; + << state << std::endl; + std::cout << std::flush; } ///////////////////////////////////////////////// -void DockChecker::OnExternalActivationEvent(const msgs::Boolean &_msg) +void DockChecker::OnExternalActivationEvent(const msgs::Pose &_msg) { - this->atEntrance = _msg.data() == 1; + // Get the state from the header. + std::string state; + for (const auto &data : _msg.header().data()) + { + if (data.key() == "state" && !data.value().empty()) + { + state = data.value(0); + break; + } + } + + this->atEntrance = state == "1"; if (this->atEntrance) { @@ -400,12 +420,16 @@ void DockChecker::OnExternalActivationEvent(const msgs::Boolean &_msg) } gzdbg << "[" << this->name << "] OnExternalActivationEvent(): " - << _msg.data() << std::endl; + << state << std::endl; + std::cout << std::flush; } /// \brief Private ScanDockScoringPlugin data class. class ScanDockScoringPlugin::Implementation { + /// \brief World entity. + public: std::string worldName; + /// \brief Parse all SDF parameters. /// \param[in] _sdf SDF elements. /// \return True when all params were successfully parsed or false otherwise. @@ -438,6 +462,9 @@ class ScanDockScoringPlugin::Implementation /// \brief Expected color sequence. public: std::vector expectedSequence; + /// \brief A transport node. + public: transport::Node node; + /// \brief A mutex. public: std::mutex mutex; }; @@ -609,6 +636,10 @@ void ScanDockScoringPlugin::Configure(const sim::Entity &_entity, { ScoringPlugin::Configure(_entity, _sdf, _ecm, _eventMgr); + sim::Entity worldEntity = _ecm.EntityByComponents(sim::components::World()); + this->dataPtr->worldName = + _ecm.Component(worldEntity)->Data(); + auto sdf = _sdf->Clone(); if (!this->dataPtr->ParseSDF(sdf)) { @@ -705,6 +736,20 @@ void ScanDockScoringPlugin::OnReady() ////////////////////////////////////////////////// void ScanDockScoringPlugin::OnRunning() { + std::function f = + [](const msgs::Boolean &_res, const bool) + { + }; + + std::string performerTopic = + "/world/" + this->dataPtr->worldName + "/level/set_performer"; + msgs::StringMsg performer; + performer.set_data(this->VehicleName()); + + // Register the vehicle as a performer. + this->dataPtr->node.Request( + performerTopic, performer, f); + if (this->dataPtr->enableColorChecker) this->dataPtr->colorChecker->Enable(); diff --git a/vrx_gz/src/ScanDockScoringPlugin.hh b/vrx_gz/src/ScanDockScoringPlugin.hh index a97342d29..a7cb287c6 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.hh +++ b/vrx_gz/src/ScanDockScoringPlugin.hh @@ -42,6 +42,27 @@ namespace vrx /// : Expected 3rd color of the sequence (RED, GREEN, BLUE, YELLOW). /// : Points granted when the color sequence is correct. /// Default value is 10. + /// : Contains at least one of the following blocks: + /// : A bay represents a potential place where a vehicle can dock. + /// It has the following required elements: + /// : The name of the bay. This is used for debugging only. + /// : The topic used to receive + /// notifications from the internal activation zone. + /// : The topic used to receive + /// notifications from the external activation zone. + /// : Minimum amount of seconds to stay docked to be + /// considered a fully successfull dock. + /// : Whether is allowed to dock in this bay or not. + /// : Required string with format _, where + /// color can be "red", "green", "blue", "yellow" and shape can be + /// "triangle", "circle", "cross", "rectangle". If this parameter is + /// present, a message will be sent in OnReady(). + /// The vehicle should dock in the bay matching this color and shape. + /// Topic to publish the symbol announcement. + /// : Points granted when the vehicle successfully + /// dock-and-undock in any bay. Default value is 10. + /// : Points granted when the vehicle successfully + /// dock-and-undock in the specified bay. Default value is 10. /// Here's an example: /// @@ -58,6 +79,38 @@ namespace vrx /// red /// green /// blue + /// + /// 15 + /// 5 + /// + /// + /// bay1 + /// /vrx/dock_2022/bay_1/contain + /// /vrx/dock_2022/bay_1_external/contain + /// /vrx/dock_2022_placard1/symbol + /// 10.0 + /// False + /// red_rectangle + /// + /// + /// bay2 + /// /vrx/dock_2022/bay_2/contain + /// /vrx/dock_2022/bay_2_external/contain + /// /vrx/dock_2022_placard2/symbol + /// 10.0 + /// True + /// blue_triangle + /// + /// + /// bay3 + /// /vrx/dock_2022/bay_3/contain + /// /vrx/dock_2022/bay_3_external/contain + /// /vrx/dock_2022_placard3/symbol + /// 10.0 + /// False + /// yellow_circle + /// + /// /// class ScanDockScoringPlugin : public ScoringPlugin { diff --git a/vrx_gz/worlds/scan_dock_deliver_task.sdf b/vrx_gz/worlds/scan_dock_deliver_task.sdf index 5a4fe8da0..5c82e21c6 100644 --- a/vrx_gz/worlds/scan_dock_deliver_task.sdf +++ b/vrx_gz/worlds/scan_dock_deliver_task.sdf @@ -532,19 +532,6 @@ dock_2022 -480 190 0 0 0 1.0 - - - @@ -573,7 +560,7 @@ /vrx/dock_2022/bay_1_external/contain /vrx/dock_2022_placard1/symbol 10.0 - True + False red_rectangle @@ -582,7 +569,7 @@ /vrx/dock_2022/bay_2_external/contain /vrx/dock_2022_placard2/symbol 10.0 - False + True blue_triangle @@ -597,16 +584,5 @@ - - - wamv - - - 4 2 2 - - - - - diff --git a/vrx_urdf/vrx_gazebo/models/cpu_cases/mesh/cpu_cases.dae b/vrx_urdf/vrx_gazebo/models/cpu_cases/mesh/cpu_cases.dae index f2a406fe5..89e0437b3 100644 --- a/vrx_urdf/vrx_gazebo/models/cpu_cases/mesh/cpu_cases.dae +++ b/vrx_urdf/vrx_gazebo/models/cpu_cases/mesh/cpu_cases.dae @@ -1,9605 +1,115 @@ - + - FBX COLLADA exporter + Blender User + Blender 3.3.1 commit date:2022-10-04, commit time:18:35, hash:b292cfe5a936 - 2019-05-07T18:12:40Z - 2019-05-07T18:12:40Z - + 2022-11-13T14:54:13 + 2022-11-13T14:54:13 + Z_UP - - - cpu_cases.png - - - - - - - - + - - + + + battery_Albedo_png + + + + + battery_Albedo_png-surface + + + + - 0.000000 0.000000 0.000000 1.000000 + 0 0 0 1 - - 0.588235 0.588235 0.588235 1.000000 - - - - - TRUE - TRUE - ADD - - - + - - 0.000000 0.000000 0.000000 1.000000 - - - 2.000000 - - - 0.000000 0.000000 0.000000 1.000000 - - - 1.000000 - - - 1.000000 1.000000 1.000000 1.000000 - - - 0.000000 - - + + 1.45 + + + + + cpu_cases_Albedo.png + + + + + + + - + - - --16.593552 -35.268177 129.687149 --15.770415 -37.737591 129.687149 --13.301003 -38.560726 129.687149 --14.533280 -39.450439 176.006958 --16.487202 -39.005096 176.006958 --16.932541 -37.051178 176.006958 --13.506402 -39.632484 130.699921 --14.871070 -41.531925 164.689804 --17.649372 -35.489513 130.699921 --19.014042 -37.388954 164.689804 --14.871060 -41.531925 173.898239 --19.014034 -37.388954 173.898239 --16.613632 -38.596741 130.699921 --17.978298 -40.496181 164.689804 --17.978291 -40.496181 173.898239 --14.786614 -41.011555 175.479782 --18.493660 -37.304512 175.479782 --17.605515 -40.123413 175.479782 --14.190949 -25.839746 129.687149 --14.190946 -5.731884 129.687149 --16.593552 -25.839746 129.687149 --17.649372 -25.839746 130.699921 --18.753498 -25.839746 158.200409 --16.593552 -5.731884 129.687149 --17.649372 -5.731883 130.699921 --18.753498 -5.731882 158.200424 --18.815815 -7.284054 159.752594 --18.815815 -24.287575 159.752594 --18.800236 -25.451702 159.364548 --18.800236 -6.119925 159.364548 --14.190949 -5.731883 158.200424 --14.190949 -6.119926 159.364548 --14.190949 -7.284054 159.752594 --14.190953 -25.839746 158.200409 --14.190953 -25.451702 159.364548 --14.190953 -24.287575 159.752594 -6.260983 -36.318645 129.687149 --8.506461 -36.318645 129.687149 -6.260983 -38.560726 129.687149 -6.260983 -39.632484 130.699921 -6.260983 -41.169285 158.200409 --8.506461 -38.560726 129.687149 --8.506461 -39.632484 130.699921 --8.506461 -41.169285 158.200409 --6.954288 -41.256023 159.752594 -4.708812 -41.256023 159.752594 -5.872939 -41.234337 159.364548 --8.118417 -41.234337 159.364548 --6.954288 -36.318645 159.752594 --8.118417 -36.318645 159.364548 --8.506461 -36.318645 158.200409 -6.260983 -36.318649 158.200409 -5.872940 -36.318649 159.364548 -4.708813 -36.318649 159.752594 --15.692151 -5.731886 176.006958 --15.692155 -25.839748 176.006958 --19.014034 -25.839746 173.898239 --18.493660 -25.839746 175.479782 --16.932541 -25.839748 176.006958 --19.014038 -25.839746 170.386932 --19.014034 -5.731886 173.898239 --19.014038 -5.731886 170.386948 --18.493660 -5.731886 175.479782 --16.932541 -5.731886 176.006958 --19.014038 -24.287575 168.834763 --19.014038 -7.284057 168.834763 --19.014038 -25.451704 169.222809 --19.014038 -6.119928 169.222809 --15.692151 -5.731886 170.386932 --15.692151 -6.119929 169.222809 --15.692151 -7.284058 168.834763 --15.692155 -24.287577 168.834763 --15.692155 -25.451706 169.222809 --15.692155 -25.839748 170.386932 --8.506461 -38.143372 176.006958 -6.260980 -38.143368 176.006958 -6.260980 -39.450439 176.006958 -6.260979 -41.531925 173.898239 -6.260979 -41.011555 175.479782 -6.260979 -41.531925 170.386948 --8.506461 -41.011555 175.479782 --8.506461 -41.531925 173.898239 --8.506461 -41.531925 170.386932 --8.506461 -39.450439 176.006958 -4.708809 -41.531925 168.834763 --6.954289 -41.531925 168.834763 -5.872936 -41.531925 169.222809 --8.118417 -41.531925 169.222809 --6.954289 -38.143372 168.834763 --8.118417 -38.143372 169.222809 -4.708809 -38.143375 168.834763 -5.872936 -38.143368 169.222809 -6.260980 -38.143368 170.386932 --8.506461 -38.143372 170.386932 --19.014042 -7.312862 164.689804 --19.014042 -24.280998 164.689804 --19.014042 -25.442301 164.689804 --19.014042 -6.153670 164.689804 --19.014038 -37.388954 170.386932 --17.978294 -40.496181 170.386932 --14.871062 -41.531925 170.386932 --19.014038 -37.388954 169.222809 --17.978294 -40.496181 169.222809 --14.871064 -41.531925 169.222809 --7.025945 -41.531925 164.689804 --8.196286 -41.531925 164.689804 --14.657264 -41.234337 159.364548 --17.764492 -40.198597 159.364548 --18.800236 -37.091366 159.364548 --18.753498 -37.026314 158.200409 --17.717754 -40.133545 158.200409 --14.610526 -41.169281 158.200409 -4.637154 -41.531925 164.689804 -5.795068 -41.531925 164.689804 -10.972301 -41.169273 158.200394 -10.972301 -37.032719 176.006958 --16.932541 0.000000 176.006958 -10.972301 -38.560726 129.687149 -10.972301 -39.632484 130.699921 -10.972301 -41.011555 175.479782 -10.972301 -41.234375 159.364563 -10.972301 -41.531925 170.386948 --18.493660 0.000000 175.479782 --19.014038 0.000000 169.222778 --8.461814 -38.700436 156.949387 --8.461814 -38.700436 155.009293 --8.461814 -39.317528 155.973785 --8.461814 -37.475731 155.973785 --1.103743 -38.700436 156.949387 --1.103743 -37.475731 156.949387 --1.103743 -37.475731 146.377563 -4.718322 -39.317539 150.531494 -5.581581 -39.317539 152.781586 -5.581581 -39.317539 146.653397 -4.718322 -39.317539 146.822098 -2.310718 -39.317528 155.009293 -1.734024 -39.317539 152.119827 -3.593332 -39.317539 145.005432 -3.544307 -39.317539 145.881287 -4.425677 -39.317539 146.167908 -5.012148 -39.317539 145.504303 -5.074028 -39.317539 153.938354 -4.304079 -39.317539 151.194901 -3.405956 -39.317539 151.690582 -4.062416 -39.317528 155.009293 -4.229142 -38.700390 149.870178 -4.229143 -38.700390 146.917694 -4.229142 -37.475731 146.917694 -4.229142 -37.475731 149.870178 -6.070762 -38.700390 153.834656 -6.070762 -37.475731 153.834656 -6.070762 -37.475731 146.557800 -6.070762 -38.700390 146.557800 -2.568247 -38.700436 156.949387 -2.568247 -37.475731 156.949387 -1.598726 -38.700390 151.513321 -1.598726 -37.475731 151.513321 -3.621114 -38.700390 144.509125 -5.344482 -38.700390 145.128250 -5.344482 -37.475731 145.128250 -3.621114 -37.475731 144.509125 -4.093343 -38.700390 146.543961 -3.516525 -38.700390 146.377594 -3.516525 -37.475731 146.377594 -4.093343 -37.475731 146.543961 -6.254330 -38.700436 156.949387 -6.254330 -37.475731 156.949387 -6.254330 -38.700436 155.009293 -6.254330 -39.317528 155.973785 -6.254330 -37.475731 155.973785 -6.254330 -37.475731 155.009293 -5.392851 -38.700424 155.009293 -5.392851 -37.475731 155.009293 -3.927212 -38.700390 150.483063 -3.927212 -37.475731 150.483063 -3.170327 -38.700390 151.037842 -3.170327 -37.475731 151.037842 -2.438744 -39.317528 155.973785 --1.103743 -39.317539 145.873962 --1.103743 -37.475731 151.616714 --1.103743 -38.700390 146.377563 --1.103743 -37.475731 144.481644 --1.103743 -39.317528 155.973785 --6.925807 -39.317539 150.531494 --6.925807 -39.317539 146.822098 --7.789065 -39.317539 146.653397 --7.789065 -39.317539 152.781586 --1.103743 -39.317539 152.243317 --3.941508 -39.317539 152.119827 --4.518202 -39.317528 155.009293 --1.103743 -39.317528 155.009293 --5.800817 -39.317539 145.005432 --7.219634 -39.317539 145.504303 --6.633162 -39.317539 146.167908 --5.751792 -39.317539 145.881287 --7.281514 -39.317539 153.938354 --6.269902 -39.317528 155.009293 --5.613441 -39.317539 151.690582 --6.511563 -39.317539 151.194901 --1.103743 -39.317539 144.985245 --6.436627 -38.700390 149.870178 --6.436627 -37.475731 149.870178 --6.436627 -37.475731 146.917694 --6.436629 -38.700390 146.917694 --8.278247 -38.700390 153.834656 --8.278247 -38.700390 146.557800 --8.278247 -37.475731 146.557800 --8.278247 -37.475731 153.834656 --4.775732 -38.700436 156.949387 --4.775732 -37.475731 156.949387 --1.103743 -38.700390 151.616714 --3.806211 -37.475731 151.513321 --3.806211 -38.700390 151.513321 --5.828599 -38.700390 144.509125 --5.828599 -37.475731 144.509125 --7.551967 -37.475731 145.128250 --7.551967 -38.700390 145.128250 --6.300828 -38.700390 146.543961 --6.300828 -37.475731 146.543961 --5.724010 -37.475731 146.377594 --5.724010 -38.700390 146.377594 --8.461814 -38.700436 156.949387 --8.461814 -37.475731 156.949387 --8.461814 -38.700436 155.009293 --8.461814 -37.475731 155.009293 --8.461814 -37.475731 155.973785 --8.461814 -39.317528 155.973785 --7.600337 -38.700424 155.009293 --7.600337 -37.475731 155.009293 --6.134698 -38.700390 150.483063 --6.134698 -37.475731 150.483063 --1.103743 -38.700390 144.481644 --5.377812 -37.475731 151.037842 --5.377812 -38.700390 151.037842 --4.646229 -39.317528 155.973785 -36.555126 -41.169281 158.200409 -36.601864 -41.234337 159.364548 -39.709095 -40.198597 159.364548 -39.662357 -40.133545 158.200409 -40.958633 -37.388954 173.898239 -40.958637 -37.388954 170.386932 -39.922894 -40.496181 170.386932 -39.922890 -40.496181 173.898239 -40.744839 -37.091366 159.364548 -40.698097 -37.026314 158.200409 -36.815662 -41.531925 170.386932 -36.815662 -41.531925 173.898239 -36.731216 -41.011555 175.479782 -36.477882 -39.450439 176.006958 -38.431801 -39.005096 176.006958 -39.550117 -40.123413 175.479782 -38.877144 -37.051178 176.006958 -40.438259 -37.304512 175.479782 -39.593975 -35.489513 130.699921 -38.538155 -35.268177 129.687149 -37.715015 -37.737591 129.687149 -38.558231 -38.596741 130.699921 -35.245605 -38.560726 129.687149 -35.451004 -39.632484 130.699921 -39.593975 -25.839746 130.699921 -38.538155 -25.839746 129.687149 -39.593975 -5.731883 130.699921 -39.593975 0.000000 130.699921 -38.538155 -5.731884 129.687149 -36.135555 -25.839746 158.200409 -36.135551 -25.839746 129.687149 -40.698097 -25.839746 158.200409 -40.744839 -25.451702 159.364548 -36.135555 -25.451702 159.364548 -40.760418 -24.287575 159.752594 -36.135555 -24.287575 159.752594 -40.760418 -7.284054 159.752594 -36.135551 -7.284054 159.752594 -40.744839 -6.119925 159.364548 -36.135551 -6.119926 159.364548 -40.698097 -5.731882 158.200424 -36.135551 -5.731883 158.200424 -15.683619 -39.632484 130.699921 -15.683619 -38.560726 129.687149 -30.451061 -39.632484 130.699921 -30.451061 -38.560726 129.687149 -28.898888 -36.318645 159.752594 -28.898888 -41.256023 159.752594 -30.063019 -41.234337 159.364548 -30.063019 -36.318645 159.364548 -30.451061 -41.169285 158.200409 -30.451061 -36.318645 158.200409 -15.683618 -36.318649 158.200409 -15.683618 -36.318645 129.687149 -15.683619 -41.169285 158.200409 -16.071663 -41.234337 159.364548 -16.071661 -36.318649 159.364548 -17.235790 -41.256023 159.752594 -17.235788 -36.318649 159.752594 -40.958633 -25.839746 173.898239 -40.438259 -25.839746 175.479782 -38.877144 -25.839748 176.006958 -40.438259 -5.731886 175.479782 -38.877144 -5.731886 176.006958 -38.877140 0.000000 176.006958 -37.636753 -6.119929 169.222809 -37.636753 -5.731886 170.386932 -40.958637 -5.731886 170.386948 -40.958637 -6.119928 169.222809 -40.958637 -7.284057 168.834763 -37.636753 -7.284058 168.834763 -40.958637 -24.287575 168.834763 -37.636757 -24.287577 168.834763 -40.958637 -25.451704 169.222809 -37.636757 -25.451706 169.222809 -40.958637 -25.839746 170.386932 -37.636757 -25.839748 170.386932 -15.683622 -41.531925 173.898239 -10.972301 -41.531925 173.898239 -15.683622 -41.011555 175.479782 -10.972301 -39.450439 176.006958 -15.683621 -39.450439 176.006958 -30.451061 -41.531925 173.898239 -30.451061 -41.011555 175.479782 -30.451061 -39.450439 176.006958 -28.898891 -41.531925 168.834763 -28.898891 -38.143372 168.834763 -30.063019 -38.143372 169.222809 -30.063019 -41.531925 169.222809 -17.235792 -38.143375 168.834763 -17.235792 -41.531925 168.834763 -16.071665 -41.531925 169.222809 -16.071665 -38.143368 169.222809 -15.683621 -38.143368 170.386932 -15.683622 -41.531925 170.386948 -30.451061 -38.143372 170.386932 -30.451061 -41.531925 170.386932 -40.698128 0.000000 158.200394 -36.135548 -5.731884 129.687149 -28.970547 -41.531925 164.689804 -30.140888 -41.531925 164.689804 -30.451061 -36.318645 129.687149 -40.958641 -6.153670 164.689804 -37.636753 -5.731886 176.006958 -40.958633 -5.731886 173.898239 -37.636757 -25.839748 176.006958 -15.683621 -38.143368 176.006958 -30.451061 -38.143372 176.006958 -40.958633 0.000000 173.898239 -40.958641 -24.280998 164.689804 -40.958641 -7.312862 164.689804 -40.958641 -25.442301 164.689804 -40.958637 -37.388954 169.222809 -39.922894 -40.496181 169.222809 -36.815666 -41.531925 169.222809 -40.958641 -37.388954 164.689804 -39.922901 -40.496181 164.689804 -36.815670 -41.531925 164.689804 -17.307447 -41.531925 164.689804 -10.972301 -41.531925 164.689804 -16.149532 -41.531925 164.689804 -10.972301 -41.531925 169.222778 -30.406414 -38.700436 155.009293 -30.406414 -39.317528 155.973785 -30.406414 -37.475731 155.973785 -30.406414 -37.475731 155.009293 -30.406414 -38.700436 156.949387 -30.406414 -37.475731 156.949387 -17.226278 -39.317539 150.531494 -17.226278 -39.317539 146.822098 -16.363020 -39.317539 146.653397 -16.363020 -39.317539 152.781586 -23.048344 -39.317539 152.243317 -20.210577 -39.317539 152.119827 -19.633884 -39.317528 155.009293 -23.048344 -39.317528 155.009293 -18.351269 -39.317539 145.005432 -16.932453 -39.317539 145.504303 -17.518925 -39.317539 146.167908 -18.400295 -39.317539 145.881287 -16.870573 -39.317539 153.938354 -17.882185 -39.317528 155.009293 -18.538645 -39.317539 151.690582 -17.640522 -39.317539 151.194901 -23.048344 -39.317539 144.985245 -23.048344 -39.317539 145.873962 -17.715460 -38.700390 149.870178 -17.715460 -37.475731 149.870178 -17.715460 -37.475731 146.917694 -17.715458 -38.700390 146.917694 -15.873839 -38.700390 153.834656 -15.873839 -38.700390 146.557800 -15.873839 -37.475731 146.557800 -15.873839 -37.475731 153.834656 -19.376354 -38.700436 156.949387 -19.376354 -37.475731 156.949387 -23.048344 -37.475731 156.949387 -23.048344 -38.700436 156.949387 -23.048344 -38.700390 151.616714 -23.048344 -37.475731 151.616714 -20.345875 -37.475731 151.513321 -20.345875 -38.700390 151.513321 -18.323486 -38.700390 144.509125 -18.323486 -37.475731 144.509125 -16.600119 -37.475731 145.128250 -16.600119 -38.700390 145.128250 -17.851257 -38.700390 146.543961 -17.851257 -37.475731 146.543961 -18.428076 -37.475731 146.377594 -18.428076 -38.700390 146.377594 -15.690271 -38.700436 156.949387 -15.690271 -37.475731 156.949387 -15.690271 -38.700436 155.009293 -15.690271 -37.475731 155.009293 -15.690271 -37.475731 155.973785 -15.690271 -39.317528 155.973785 -16.551750 -38.700424 155.009293 -16.551750 -37.475731 155.009293 -18.017389 -38.700390 150.483063 -18.017389 -37.475731 150.483063 -23.048344 -37.475731 146.377563 -23.048344 -38.700390 146.377563 -23.048344 -38.700390 144.481644 -23.048344 -37.475731 144.481644 -18.774273 -37.475731 151.037842 -18.774273 -38.700390 151.037842 -19.505857 -39.317528 155.973785 -23.048344 -39.317528 155.973785 -28.870407 -39.317539 150.531494 -29.733665 -39.317539 152.781586 -29.733665 -39.317539 146.653397 -28.870407 -39.317539 146.822098 -26.462803 -39.317528 155.009293 -25.886108 -39.317539 152.119827 -27.745419 -39.317539 145.005432 -27.696392 -39.317539 145.881287 -28.577763 -39.317539 146.167908 -29.164234 -39.317539 145.504303 -29.226116 -39.317539 153.938354 -28.456165 -39.317539 151.194901 -27.558041 -39.317539 151.690582 -28.214504 -39.317528 155.009293 -28.381229 -38.700390 149.870178 -28.381229 -38.700390 146.917694 -28.381229 -37.475731 146.917694 -28.381229 -37.475731 149.870178 -30.222847 -38.700390 153.834656 -30.222847 -37.475731 153.834656 -30.222847 -37.475731 146.557800 -30.222847 -38.700390 146.557800 -26.720333 -38.700436 156.949387 -26.720333 -37.475731 156.949387 -25.750813 -38.700390 151.513321 -25.750813 -37.475731 151.513321 -27.773201 -38.700390 144.509125 -29.496567 -38.700390 145.128250 -29.496567 -37.475731 145.128250 -27.773201 -37.475731 144.509125 -28.245430 -38.700390 146.543961 -27.668610 -38.700390 146.377594 -27.668610 -37.475731 146.377594 -28.245430 -37.475731 146.543961 -30.406414 -38.700436 156.949387 -30.406414 -38.700436 155.009293 -30.406414 -39.317528 155.973785 -30.406414 -37.475731 155.973785 -29.544937 -38.700424 155.009293 -29.544937 -37.475731 155.009293 -28.079300 -38.700390 150.483063 -28.079300 -37.475731 150.483063 -27.322414 -38.700390 151.037842 -27.322414 -37.475731 151.037842 -26.590830 -39.317528 155.973785 --14.610526 41.169281 158.200409 --14.657264 41.234337 159.364548 --17.764492 40.198597 159.364548 --17.717754 40.133545 158.200409 --19.014034 37.388954 173.898239 --19.014038 37.388954 170.386932 --17.978294 40.496181 170.386932 --17.978291 40.496181 173.898239 --18.800236 37.091366 159.364548 --18.753498 37.026314 158.200409 --14.871062 41.531925 170.386932 --14.871060 41.531925 173.898239 --14.786614 41.011555 175.479782 --14.533280 39.450439 176.006958 --16.487202 39.005096 176.006958 --17.605515 40.123413 175.479782 --16.932541 37.051178 176.006958 --18.493660 37.304512 175.479782 --17.649372 35.489513 130.699921 --16.593552 35.268177 129.687149 --15.770415 37.737591 129.687149 --16.613632 38.596741 130.699921 --13.301003 38.560726 129.687149 --13.506402 39.632484 130.699921 --17.649372 25.839746 130.699921 --16.593552 25.839746 129.687149 --17.649372 5.731883 130.699921 --17.649372 0.000000 130.699921 --16.593552 0.000000 129.687149 --16.593552 5.731884 129.687149 --14.190953 25.839746 158.200409 --14.190949 25.839746 129.687149 --18.753498 25.839746 158.200409 --18.800236 25.451702 159.364548 --14.190953 25.451702 159.364548 --18.815815 24.287575 159.752594 --14.190953 24.287575 159.752594 --18.815815 7.284054 159.752594 --14.190949 7.284054 159.752594 --18.800236 6.119925 159.364548 --14.190949 6.119926 159.364548 --18.753498 5.731882 158.200424 --14.190949 5.731883 158.200424 -6.260983 39.632484 130.699921 -6.260983 38.560726 129.687149 -10.972301 38.560726 129.687149 -10.972301 39.632484 130.699921 --8.506461 39.632484 130.699921 --8.506461 38.560726 129.687149 --6.954288 36.318645 159.752594 --6.954288 41.256023 159.752594 --8.118417 41.234337 159.364548 --8.118417 36.318645 159.364548 --8.506461 41.169285 158.200409 --8.506461 36.318645 158.200409 -6.260983 36.318649 158.200409 -6.260983 36.318645 129.687149 -6.260983 41.169285 158.200409 -5.872939 41.234337 159.364548 -5.872940 36.318649 159.364548 -4.708812 41.256023 159.752594 -4.708813 36.318649 159.752594 --19.014034 25.839746 173.898239 --18.493660 25.839746 175.479782 --16.932541 25.839748 176.006958 --18.493660 5.731886 175.479782 --16.932541 5.731886 176.006958 --15.692151 6.119929 169.222809 --15.692151 5.731886 170.386932 --19.014038 5.731886 170.386948 --19.014038 6.119928 169.222809 --19.014038 7.284057 168.834763 --15.692151 7.284058 168.834763 --19.014038 24.287575 168.834763 --15.692155 24.287577 168.834763 --19.014038 25.451704 169.222809 --15.692155 25.451706 169.222809 --19.014038 25.839746 170.386932 --15.692155 25.839748 170.386932 -6.260979 41.531925 173.898239 -10.972301 41.531925 173.898239 -10.972301 41.011555 175.479782 -6.260979 41.011555 175.479782 -10.972301 39.450439 176.006958 -6.260980 39.450439 176.006958 --8.506461 41.531925 173.898239 --8.506461 41.011555 175.479782 --8.506461 39.450439 176.006958 --6.954289 41.531925 168.834763 --6.954289 38.143372 168.834763 --8.118417 38.143372 169.222809 --8.118417 41.531925 169.222809 -4.708809 38.143375 168.834763 -4.708809 41.531925 168.834763 -5.872936 41.531925 169.222809 -5.872936 38.143368 169.222809 -6.260980 38.143368 170.386932 -6.260979 41.531925 170.386948 --8.506461 38.143372 170.386932 --8.506461 41.531925 170.386932 --18.753525 0.000000 158.200394 --14.190946 5.731884 129.687149 --7.025945 41.531925 164.689804 --8.196286 41.531925 164.689804 --8.506461 36.318645 129.687149 --19.014042 0.000000 164.689804 --19.014042 6.153670 164.689804 --15.692151 5.731886 176.006958 --19.014034 5.731886 173.898239 --15.692155 25.839748 176.006958 -10.972301 0.000000 176.006958 -6.260980 38.143368 176.006958 --8.506461 38.143372 176.006958 --19.014034 0.000000 173.898239 -10.972301 37.032719 176.006958 --19.014042 24.280998 164.689804 --19.014042 7.312862 164.689804 --19.014042 25.442301 164.689804 --19.014038 0.000000 170.386948 --18.800209 0.000000 159.364563 --19.014038 37.388954 169.222809 --17.978294 40.496181 169.222809 --14.871064 41.531925 169.222809 --19.014042 37.388954 164.689804 --17.978298 40.496181 164.689804 --14.871070 41.531925 164.689804 -4.637154 41.531925 164.689804 -10.972301 41.234375 159.364563 -10.972301 41.531925 164.689804 -5.795068 41.531925 164.689804 -10.972301 41.531925 170.386948 -10.972301 41.169273 158.200394 -10.972301 41.531925 169.222778 --8.461814 38.700436 155.009293 --8.461814 39.317528 155.973785 --8.461814 37.475731 155.973785 --8.461814 37.475731 155.009293 --8.461814 38.700436 156.949387 --8.461814 37.475731 156.949387 -4.718322 39.317539 150.531494 -4.718322 39.317539 146.822098 -5.581581 39.317539 146.653397 -5.581581 39.317539 152.781586 --1.103743 39.317539 152.243317 -1.734024 39.317539 152.119827 -2.310718 39.317528 155.009293 --1.103743 39.317528 155.009293 -3.593332 39.317539 145.005432 -5.012148 39.317539 145.504303 -4.425677 39.317539 146.167908 -3.544307 39.317539 145.881287 -5.074028 39.317539 153.938354 -4.062416 39.317528 155.009293 -3.405956 39.317539 151.690582 -4.304079 39.317539 151.194901 --1.103743 39.317539 144.985245 --1.103743 39.317539 145.873962 -4.229142 38.700390 149.870178 -4.229142 37.475731 149.870178 -4.229142 37.475731 146.917694 -4.229143 38.700390 146.917694 -6.070762 38.700390 153.834656 -6.070762 38.700390 146.557800 -6.070762 37.475731 146.557800 -6.070762 37.475731 153.834656 -2.568247 38.700436 156.949387 -2.568247 37.475731 156.949387 --1.103743 37.475731 156.949387 --1.103743 38.700436 156.949387 --1.103743 38.700390 151.616714 --1.103743 37.475731 151.616714 -1.598726 37.475731 151.513321 -1.598726 38.700390 151.513321 -3.621114 38.700390 144.509125 -3.621114 37.475731 144.509125 -5.344482 37.475731 145.128250 -5.344482 38.700390 145.128250 -4.093343 38.700390 146.543961 -4.093343 37.475731 146.543961 -3.516525 37.475731 146.377594 -3.516525 38.700390 146.377594 -6.254330 38.700436 156.949387 -6.254330 37.475731 156.949387 -6.254330 38.700436 155.009293 -6.254330 37.475731 155.009293 -6.254330 37.475731 155.973785 -6.254330 39.317528 155.973785 -5.392851 38.700424 155.009293 -5.392851 37.475731 155.009293 -3.927212 38.700390 150.483063 -3.927212 37.475731 150.483063 --1.103743 37.475731 146.377563 --1.103743 38.700390 146.377563 --1.103743 38.700390 144.481644 --1.103743 37.475731 144.481644 -3.170327 37.475731 151.037842 -3.170327 38.700390 151.037842 -2.438744 39.317528 155.973785 --1.103743 39.317528 155.973785 --6.925807 39.317539 150.531494 --7.789065 39.317539 152.781586 --7.789065 39.317539 146.653397 --6.925807 39.317539 146.822098 --4.518202 39.317528 155.009293 --3.941508 39.317539 152.119827 --5.800817 39.317539 145.005432 --5.751792 39.317539 145.881287 --6.633162 39.317539 146.167908 --7.219634 39.317539 145.504303 --7.281514 39.317539 153.938354 --6.511563 39.317539 151.194901 --5.613441 39.317539 151.690582 --6.269902 39.317528 155.009293 --6.436627 38.700390 149.870178 --6.436629 38.700390 146.917694 --6.436627 37.475731 146.917694 --6.436627 37.475731 149.870178 --8.278247 38.700390 153.834656 --8.278247 37.475731 153.834656 --8.278247 37.475731 146.557800 --8.278247 38.700390 146.557800 --4.775732 38.700436 156.949387 --4.775732 37.475731 156.949387 --3.806211 38.700390 151.513321 --3.806211 37.475731 151.513321 --5.828599 38.700390 144.509125 --7.551967 38.700390 145.128250 --7.551967 37.475731 145.128250 --5.828599 37.475731 144.509125 --6.300828 38.700390 146.543961 --5.724010 38.700390 146.377594 --5.724010 37.475731 146.377594 --6.300828 37.475731 146.543961 --8.461814 38.700436 156.949387 --8.461814 38.700436 155.009293 --8.461814 39.317528 155.973785 --8.461814 37.475731 155.973785 --7.600337 38.700424 155.009293 --7.600337 37.475731 155.009293 --6.134698 38.700390 150.483063 --6.134698 37.475731 150.483063 --5.377812 38.700390 151.037842 --5.377812 37.475731 151.037842 --4.646229 39.317528 155.973785 -36.555126 41.169281 158.200409 -39.662357 40.133545 158.200409 -39.709095 40.198597 159.364548 -36.601864 41.234337 159.364548 -40.958633 37.388954 173.898239 -39.922890 40.496181 173.898239 -39.922894 40.496181 170.386932 -40.958637 37.388954 170.386932 -40.698097 37.026314 158.200409 -40.744839 37.091366 159.364548 -36.815662 41.531925 173.898239 -36.815662 41.531925 170.386932 -36.731216 41.011555 175.479782 -39.550117 40.123413 175.479782 -38.431801 39.005096 176.006958 -36.477882 39.450439 176.006958 -40.438259 37.304512 175.479782 -38.877144 37.051178 176.006958 -39.593975 35.489513 130.699921 -38.558231 38.596741 130.699921 -37.715015 37.737591 129.687149 -38.538155 35.268177 129.687149 -35.451004 39.632484 130.699921 -35.245605 38.560726 129.687149 -38.538155 25.839746 129.687149 -39.593975 25.839746 130.699921 -39.593975 5.731883 130.699921 -38.538155 5.731884 129.687149 -38.538155 0.000000 129.687149 -36.135555 25.839746 158.200409 -40.698097 25.839746 158.200409 -36.135551 25.839746 129.687149 -36.135555 25.451702 159.364548 -40.744839 25.451702 159.364548 -36.135555 24.287575 159.752594 -40.760418 24.287575 159.752594 -36.135551 7.284054 159.752594 -40.760418 7.284054 159.752594 -36.135551 6.119926 159.364548 -40.744839 6.119925 159.364548 -36.135551 5.731883 158.200424 -40.698097 5.731882 158.200424 -15.683619 39.632484 130.699921 -15.683619 38.560726 129.687149 -30.451061 39.632484 130.699921 -30.451061 38.560726 129.687149 -28.898888 36.318645 159.752594 -30.063019 36.318645 159.364548 -30.063019 41.234337 159.364548 -28.898888 41.256023 159.752594 -30.451061 36.318645 158.200409 -30.451061 41.169285 158.200409 -15.683618 36.318649 158.200409 -15.683619 41.169285 158.200409 -15.683618 36.318645 129.687149 -16.071661 36.318649 159.364548 -16.071663 41.234337 159.364548 -17.235788 36.318649 159.752594 -17.235790 41.256023 159.752594 -40.958633 25.839746 173.898239 -40.438259 25.839746 175.479782 -38.877144 25.839748 176.006958 -40.438259 5.731886 175.479782 -40.438259 0.000000 175.479782 -38.877144 5.731886 176.006958 -37.636753 6.119929 169.222809 -40.958637 6.119928 169.222809 -40.958637 5.731886 170.386948 -37.636753 5.731886 170.386932 -40.958637 7.284057 168.834763 -37.636753 7.284058 168.834763 -40.958637 24.287575 168.834763 -37.636757 24.287577 168.834763 -40.958637 25.451704 169.222809 -37.636757 25.451706 169.222809 -40.958637 25.839746 170.386932 -37.636757 25.839748 170.386932 -15.683622 41.531925 173.898239 -15.683622 41.011555 175.479782 -15.683621 39.450439 176.006958 -30.451061 41.531925 173.898239 -30.451061 41.011555 175.479782 -30.451061 39.450439 176.006958 -28.898891 41.531925 168.834763 -30.063019 41.531925 169.222809 -30.063019 38.143372 169.222809 -28.898891 38.143372 168.834763 -17.235792 38.143375 168.834763 -17.235792 41.531925 168.834763 -16.071665 41.531925 169.222809 -16.071665 38.143368 169.222809 -15.683621 38.143368 170.386932 -15.683622 41.531925 170.386948 -30.451061 41.531925 170.386932 -30.451061 38.143372 170.386932 -36.135548 5.731884 129.687149 -30.140888 41.531925 164.689804 -28.970547 41.531925 164.689804 -30.451061 36.318645 129.687149 -40.958641 6.153670 164.689804 -40.958641 0.000000 164.689804 -40.958637 0.000000 169.222778 -40.958633 5.731886 173.898239 -37.636753 5.731886 176.006958 -37.636757 25.839748 176.006958 -15.683621 38.143368 176.006958 -30.451061 38.143372 176.006958 -40.958641 7.312862 164.689804 -40.958641 24.280998 164.689804 -40.958641 25.442301 164.689804 -40.958637 0.000000 170.386948 -40.744812 0.000000 159.364563 -40.958637 37.388954 169.222809 -39.922894 40.496181 169.222809 -36.815666 41.531925 169.222809 -40.958641 37.388954 164.689804 -39.922901 40.496181 164.689804 -36.815670 41.531925 164.689804 -17.307447 41.531925 164.689804 -16.149532 41.531925 164.689804 -30.406414 38.700436 155.009293 -30.406414 37.475731 155.009293 -30.406414 37.475731 155.973785 -30.406414 39.317528 155.973785 -30.406414 37.475731 156.949387 -30.406414 38.700436 156.949387 -17.226278 39.317539 150.531494 -16.363020 39.317539 152.781586 -16.363020 39.317539 146.653397 -17.226278 39.317539 146.822098 -23.048344 39.317539 152.243317 -23.048344 39.317528 155.009293 -19.633884 39.317528 155.009293 -20.210577 39.317539 152.119827 -18.351269 39.317539 145.005432 -18.400295 39.317539 145.881287 -17.518925 39.317539 146.167908 -16.932453 39.317539 145.504303 -16.870573 39.317539 153.938354 -17.640522 39.317539 151.194901 -18.538645 39.317539 151.690582 -17.882185 39.317528 155.009293 -23.048344 39.317539 144.985245 -23.048344 39.317539 145.873962 -17.715460 38.700390 149.870178 -17.715458 38.700390 146.917694 -17.715460 37.475731 146.917694 -17.715460 37.475731 149.870178 -15.873839 38.700390 153.834656 -15.873839 37.475731 153.834656 -15.873839 37.475731 146.557800 -15.873839 38.700390 146.557800 -19.376354 38.700436 156.949387 -23.048344 38.700436 156.949387 -23.048344 37.475731 156.949387 -19.376354 37.475731 156.949387 -23.048344 38.700390 151.616714 -20.345875 38.700390 151.513321 -20.345875 37.475731 151.513321 -23.048344 37.475731 151.616714 -18.323486 38.700390 144.509125 -16.600119 38.700390 145.128250 -16.600119 37.475731 145.128250 -18.323486 37.475731 144.509125 -17.851257 38.700390 146.543961 -18.428076 38.700390 146.377594 -18.428076 37.475731 146.377594 -17.851257 37.475731 146.543961 -15.690271 38.700436 156.949387 -15.690271 37.475731 156.949387 -15.690271 38.700436 155.009293 -15.690271 39.317528 155.973785 -15.690271 37.475731 155.973785 -15.690271 37.475731 155.009293 -16.551750 38.700424 155.009293 -16.551750 37.475731 155.009293 -18.017389 38.700390 150.483063 -18.017389 37.475731 150.483063 -23.048344 38.700390 146.377563 -23.048344 37.475731 146.377563 -23.048344 38.700390 144.481644 -23.048344 37.475731 144.481644 -18.774273 38.700390 151.037842 -18.774273 37.475731 151.037842 -23.048344 39.317528 155.973785 -19.505857 39.317528 155.973785 -28.870407 39.317539 150.531494 -28.870407 39.317539 146.822098 -29.733665 39.317539 146.653397 -29.733665 39.317539 152.781586 -25.886108 39.317539 152.119827 -26.462803 39.317528 155.009293 -27.745419 39.317539 145.005432 -29.164234 39.317539 145.504303 -28.577763 39.317539 146.167908 -27.696392 39.317539 145.881287 -29.226116 39.317539 153.938354 -28.214504 39.317528 155.009293 -27.558041 39.317539 151.690582 -28.456165 39.317539 151.194901 -28.381229 38.700390 149.870178 -28.381229 37.475731 149.870178 -28.381229 37.475731 146.917694 -28.381229 38.700390 146.917694 -30.222847 38.700390 153.834656 -30.222847 38.700390 146.557800 -30.222847 37.475731 146.557800 -30.222847 37.475731 153.834656 -26.720333 38.700436 156.949387 -26.720333 37.475731 156.949387 -25.750813 37.475731 151.513321 -25.750813 38.700390 151.513321 -27.773201 38.700390 144.509125 -27.773201 37.475731 144.509125 -29.496567 37.475731 145.128250 -29.496567 38.700390 145.128250 -28.245430 38.700390 146.543961 -28.245430 37.475731 146.543961 -27.668610 37.475731 146.377594 -27.668610 38.700390 146.377594 -30.406414 38.700436 156.949387 -30.406414 38.700436 155.009293 -30.406414 37.475731 155.973785 -30.406414 39.317528 155.973785 -29.544937 38.700424 155.009293 -29.544937 37.475731 155.009293 -28.079300 38.700390 150.483063 -28.079300 37.475731 150.483063 -27.322414 37.475731 151.037842 -27.322414 38.700390 151.037842 -26.590830 39.317528 155.973785 --8.461814 -37.475731 156.949387 --8.461814 -37.475731 155.009293 -30.406414 -37.475731 155.009293 -30.406414 -37.475731 156.949387 --8.461814 37.475731 155.009293 --8.461814 37.475731 156.949387 -30.406414 37.475731 155.009293 -30.406414 37.475731 156.949387 -37.636749 0.000000 176.006958 --15.692151 0.000000 176.006958 --54.576832 29.057657 130.149490 --54.703037 30.905771 149.873047 --54.052593 28.681145 153.535339 --56.171177 30.846027 149.873047 --55.428577 31.588629 153.237854 --53.350780 29.310871 129.687180 --55.356113 30.047092 147.802063 --54.093380 5.291624 129.687180 --54.093380 11.723294 129.687180 --54.093380 22.302038 129.687180 --54.576832 5.250237 130.149490 --54.576832 11.771256 130.149490 --54.576832 22.254076 130.149490 --55.356113 3.532016 147.802063 --55.356106 13.511790 147.802063 --55.356113 20.513544 147.802063 --51.859997 4.799234 129.687073 --53.109226 3.079486 147.357056 --52.355499 4.752643 130.150406 --51.860020 21.794851 129.687286 --51.860020 12.230479 129.687286 --52.353741 12.268663 130.148636 --53.109241 13.963755 147.357285 --53.109241 20.061579 147.357285 --52.353741 21.756670 130.148636 --37.354477 28.402401 157.245361 --54.052601 0.000001 153.535339 --41.010628 29.423746 153.535339 --48.926956 29.423746 153.535339 --52.259315 28.402401 157.245361 --53.001915 27.659803 157.245361 --53.001915 0.000001 157.245361 --48.399532 28.795618 155.817001 --41.522289 28.795618 155.817001 --41.010628 26.993145 153.535339 --48.926956 26.993145 153.535339 --48.399532 26.993145 155.817001 --41.522289 26.993145 155.817001 --53.834232 29.800255 130.149490 --55.445637 30.163170 149.873047 --53.310001 29.423746 153.535339 --55.428577 31.588629 149.873047 --56.171177 30.846027 153.237854 --54.093372 28.568272 129.687180 --54.613514 30.789690 147.802063 --54.391193 29.614607 130.149490 --55.259983 30.720119 149.873047 --53.866955 29.238098 153.535339 --55.985531 31.402977 149.873047 --55.985531 31.402977 153.237854 --53.907726 29.125223 129.687180 --55.170460 30.604038 147.802063 --52.816261 28.216753 157.245361 --51.859997 0.000001 129.687073 --55.356106 0.000001 147.802063 --37.354477 31.588629 153.237854 --37.354477 29.310871 129.687180 --52.816269 -28.216753 157.245361 --53.001915 -27.659803 157.245361 --37.354477 -28.402401 157.245361 --52.259315 -28.402401 157.245361 --52.355499 -4.752642 130.150406 --52.355499 0.000001 130.150406 --53.109226 0.000001 147.357056 --53.109226 -3.079484 147.357056 --56.171185 -30.846027 149.873047 --56.171177 0.000001 149.873047 --56.171177 0.000001 153.237854 --56.171185 -30.846027 153.237854 --55.445637 -30.163170 149.873047 --55.445637 0.000001 149.873047 --53.310001 -29.423746 153.535339 --48.926956 -29.423746 153.535339 --41.010632 -29.423746 153.535339 --37.354477 -31.588629 153.237854 --55.428585 -31.588629 153.237854 --54.052601 -28.681145 153.535339 --53.350780 -29.310871 129.687180 --53.834240 -29.800255 130.149490 --37.354477 -29.800255 130.149490 --37.354477 -29.310871 129.687180 --54.613514 -30.789690 147.802063 --54.703037 -30.905771 149.873047 --55.356113 -20.513544 147.802063 --55.356113 -30.047092 147.802063 --54.576839 -29.057657 130.149490 --54.576839 -22.254076 130.149490 --53.109241 -13.963753 147.357285 --53.109241 -20.061579 147.357285 --52.353748 -21.756670 130.148636 --52.353741 -12.268661 130.148636 --55.356113 -3.532014 147.802063 --55.356106 -13.511788 147.802063 --54.576832 -11.771255 130.149490 --54.576832 -5.250235 130.149490 --54.093380 -28.568272 129.687180 --54.093380 -22.302038 129.687180 --51.860020 -21.794851 129.687286 --51.860020 -12.230477 129.687286 --54.093380 -11.723292 129.687180 --54.093380 -5.291622 129.687180 --51.859997 -4.799233 129.687073 --37.354477 -31.588629 149.873047 --55.428585 -31.588629 149.873047 --41.010632 -26.993145 153.535339 --48.926956 -26.993145 153.535339 --48.399532 -26.993145 155.817001 --41.522293 -26.993145 155.817001 --48.399532 -28.795618 155.817001 --41.522293 -28.795618 155.817001 --55.259983 -30.720119 149.873047 --55.170467 -30.604038 147.802063 --55.985531 -31.402977 149.873047 --55.985531 -31.402977 153.237854 --53.866955 -29.238098 153.535339 --53.907726 -29.125223 129.687180 --54.391193 -29.614607 130.149490 --21.892693 28.216753 157.245361 --21.707043 27.659803 157.245361 --21.707043 -0.000001 157.245361 --37.354477 0.000000 157.245361 --22.449642 28.402401 157.245361 --22.353458 4.752642 130.150406 --22.353458 -0.000001 130.150406 --21.599731 -0.000001 147.357056 --21.599731 3.079484 147.357056 --18.537777 30.846027 149.873047 --18.537781 -0.000001 149.873047 --18.537781 -0.000001 153.237854 --18.537777 30.846027 153.237854 --19.263321 30.163170 149.873047 --19.263321 -0.000001 149.873047 --21.398952 29.423746 153.535339 --25.781998 29.423746 153.535339 --33.698326 29.423746 153.535339 --37.354477 29.423746 153.535339 --19.280373 31.588629 153.237854 --20.656357 28.681145 153.535339 --20.656357 -0.000001 153.535339 --21.358177 29.310871 129.687180 --20.874718 29.800255 130.149490 --37.354477 29.800255 130.149490 --20.095440 30.789690 147.802063 --20.005920 30.905771 149.873047 --37.354477 30.905771 149.873047 --37.354477 30.789690 147.802078 --19.352844 20.513544 147.802063 --19.352844 30.047092 147.802063 --20.132122 29.057657 130.149490 --20.132118 22.254076 130.149490 --21.599716 13.963753 147.357285 --21.599716 20.061579 147.357285 --22.355209 21.756670 130.148636 --22.355217 12.268661 130.148636 --19.352844 3.532014 147.802063 --19.352848 13.511788 147.802063 --20.132122 11.771255 130.149490 --20.132122 5.250235 130.149490 --20.615578 28.568272 129.687180 --20.615578 22.302038 129.687180 --22.848938 21.794851 129.687286 --22.848938 12.230477 129.687286 --20.615578 11.723292 129.687180 --20.615578 5.291622 129.687180 --22.848957 4.799233 129.687073 --37.354477 31.588629 149.873047 --19.280373 31.588629 149.873047 --33.698326 26.993145 153.535339 --25.781998 26.993145 153.535339 --26.309425 26.993145 155.817001 --33.186665 26.993145 155.817001 --22.848957 -0.000001 129.687073 --19.352848 -0.000001 147.802063 --26.309425 28.795618 155.817001 --33.186665 28.795618 155.817001 --19.448971 30.720119 149.873047 --19.538490 30.604038 147.802063 --18.723427 31.402977 149.873047 --18.723427 31.402977 153.237854 --20.842003 29.238098 153.535339 --20.801228 29.125223 129.687180 --20.317768 29.614607 130.149490 --21.892696 -28.216753 157.245361 --22.449642 -28.402401 157.245361 --21.707043 -27.659803 157.245361 --22.353458 -4.752643 130.150406 --21.599731 -3.079486 147.357056 --18.537781 -30.846027 149.873047 --18.537781 -30.846027 153.237854 --19.263321 -30.163170 149.873047 --21.398952 -29.423746 153.535339 --19.280380 -31.588629 153.237854 --37.354477 -29.423746 153.535339 --33.698330 -29.423746 153.535339 --25.782001 -29.423746 153.535339 --20.656361 -28.681145 153.535339 --21.358177 -29.310871 129.687180 --20.874722 -29.800255 130.149490 --20.095444 -30.789690 147.802063 --37.354477 -30.789690 147.802078 --37.354477 -30.905771 149.873047 --20.005920 -30.905771 149.873047 --19.352844 -20.513544 147.802063 --20.132122 -22.254076 130.149490 --20.132122 -29.057657 130.149490 --19.352844 -30.047092 147.802063 --21.599716 -13.963755 147.357285 --22.355217 -12.268663 130.148636 --22.355217 -21.756670 130.148636 --21.599716 -20.061579 147.357285 --19.352844 -3.532016 147.802063 --20.132122 -5.250237 130.149490 --20.132122 -11.771256 130.149490 --19.352848 -13.511790 147.802063 --20.615578 -22.302038 129.687180 --20.615582 -28.568272 129.687180 --22.848938 -12.230479 129.687286 --22.848938 -21.794851 129.687286 --20.615578 -5.291624 129.687180 --20.615578 -11.723294 129.687180 --22.848957 -4.799234 129.687073 --19.280380 -31.588629 149.873047 --33.698330 -26.993145 153.535339 --33.186668 -26.993145 155.817001 --26.309425 -26.993145 155.817001 --25.782001 -26.993145 153.535339 --26.309425 -28.795618 155.817001 --33.186668 -28.795618 155.817001 --19.538494 -30.604038 147.802063 --19.448975 -30.720119 149.873047 --18.723427 -31.402977 153.237854 --18.723427 -31.402977 149.873047 --20.842007 -29.238098 153.535339 --20.317772 -29.614607 130.149490 --20.801228 -29.125223 129.687180 - + + -16.59355 -35.26818 129.6871 -15.77042 -37.73759 129.6871 -13.301 -38.56072 129.6871 -14.53328 -39.45044 176.007 -16.4872 -39.0051 176.007 -16.93254 -37.05117 176.007 -13.5064 -39.63248 130.6999 -14.87107 -41.53192 164.6898 -17.64937 -35.48951 130.6999 -19.01404 -37.38895 164.6898 -14.87106 -41.53192 173.8982 -19.01403 -37.38895 173.8982 -16.61363 -38.59674 130.6999 -17.9783 -40.49618 164.6898 -17.97829 -40.49618 173.8982 -14.78661 -41.01155 175.4798 -18.49366 -37.30451 175.4798 -17.60552 -40.12341 175.4798 -14.19095 -25.83975 129.6871 -14.19095 -5.731884 129.6871 -16.59355 -25.83975 129.6871 -17.64937 -25.83975 130.6999 -18.7535 -25.83975 158.2004 -16.59355 -5.731884 129.6871 -17.64937 -5.731883 130.6999 -18.7535 -5.731882 158.2004 -18.81582 -7.284054 159.7526 -18.81582 -24.28758 159.7526 -18.80024 -25.4517 159.3645 -18.80024 -6.119925 159.3645 -14.19095 -5.731883 158.2004 -14.19095 -6.119926 159.3645 -14.19095 -7.284054 159.7526 -14.19095 -25.83975 158.2004 -14.19095 -25.4517 159.3645 -14.19095 -24.28758 159.7526 6.260983 -36.31864 129.6871 -8.506462 -36.31864 129.6871 6.260983 -38.56072 129.6871 6.260983 -39.63248 130.6999 6.260983 -41.16928 158.2004 -8.506462 -38.56072 129.6871 -8.506462 -39.63248 130.6999 -8.506462 -41.16928 158.2004 -6.954288 -41.25602 159.7526 4.708812 -41.25602 159.7526 5.872939 -41.23434 159.3645 -8.118417 -41.23434 159.3645 -6.954288 -36.31864 159.7526 -8.118417 -36.31864 159.3645 -8.506462 -36.31864 158.2004 6.260983 -36.31865 158.2004 5.87294 -36.31865 159.3645 4.708813 -36.31865 159.7526 -15.69215 -5.731886 176.007 -15.69215 -25.83975 176.007 -19.01403 -25.83975 173.8982 -18.49366 -25.83975 175.4798 -16.93254 -25.83975 176.007 -19.01404 -25.83975 170.3869 -19.01403 -5.731886 173.8982 -19.01404 -5.731886 170.3869 -18.49366 -5.731886 175.4798 -16.93254 -5.731886 176.007 -19.01404 -24.28758 168.8348 -19.01404 -7.284057 168.8348 -19.01404 -25.4517 169.2228 -19.01404 -6.119928 169.2228 -15.69215 -5.731886 170.3869 -15.69215 -6.119929 169.2228 -15.69215 -7.284058 168.8348 -15.69215 -24.28758 168.8348 -15.69215 -25.45171 169.2228 -15.69215 -25.83975 170.3869 -8.506462 -38.14337 176.007 6.26098 -38.14337 176.007 6.26098 -39.45044 176.007 6.260979 -41.53192 173.8982 6.260979 -41.01155 175.4798 6.260979 -41.53192 170.3869 -8.506462 -41.01155 175.4798 -8.506462 -41.53192 173.8982 -8.506462 -41.53192 170.3869 -8.506462 -39.45044 176.007 4.708809 -41.53192 168.8348 -6.954289 -41.53192 168.8348 5.872936 -41.53192 169.2228 -8.118417 -41.53192 169.2228 -6.954289 -38.14337 168.8348 -8.118417 -38.14337 169.2228 4.708809 -38.14337 168.8348 5.872936 -38.14337 169.2228 6.26098 -38.14337 170.3869 -8.506462 -38.14337 170.3869 -19.01404 -7.312862 164.6898 -19.01404 -24.281 164.6898 -19.01404 -25.4423 164.6898 -19.01404 -6.15367 164.6898 -19.01404 -37.38895 170.3869 -17.9783 -40.49618 170.3869 -14.87106 -41.53192 170.3869 -19.01404 -37.38895 169.2228 -17.9783 -40.49618 169.2228 -14.87106 -41.53192 169.2228 -7.025945 -41.53192 164.6898 -8.196287 -41.53192 164.6898 -14.65726 -41.23434 159.3645 -17.76449 -40.1986 159.3645 -18.80024 -37.09137 159.3645 -18.7535 -37.02631 158.2004 -17.71776 -40.13354 158.2004 -14.61053 -41.16928 158.2004 4.637154 -41.53192 164.6898 5.795068 -41.53192 164.6898 10.9723 -41.16927 158.2004 10.9723 -37.03272 176.007 -16.93254 0 176.007 10.9723 -38.56072 129.6871 10.9723 -39.63248 130.6999 10.9723 -41.01155 175.4798 10.9723 -41.23437 159.3646 10.9723 -41.53192 170.3869 -18.49366 0 175.4798 -19.01404 0 169.2228 -1.103743 -38.70043 156.9494 -1.103743 -37.47573 156.9494 -1.103743 -37.47573 146.3776 4.718322 -39.31754 150.5315 5.581581 -39.31754 152.7816 5.581581 -39.31754 146.6534 4.718322 -39.31754 146.8221 2.310718 -39.31753 155.0093 1.734024 -39.31754 152.1198 3.593332 -39.31754 145.0054 3.544307 -39.31754 145.8813 4.425677 -39.31754 146.1679 5.012148 -39.31754 145.5043 5.074028 -39.31754 153.9384 4.304079 -39.31754 151.1949 3.405956 -39.31754 151.6906 4.062416 -39.31753 155.0093 4.229142 -38.70039 149.8702 4.229143 -38.70039 146.9177 4.229142 -37.47573 146.9177 4.229142 -37.47573 149.8702 6.070762 -38.70039 153.8347 6.070762 -37.47573 153.8347 6.070762 -37.47573 146.5578 6.070762 -38.70039 146.5578 2.568247 -38.70043 156.9494 2.568247 -37.47573 156.9494 1.598726 -38.70039 151.5133 1.598726 -37.47573 151.5133 3.621114 -38.70039 144.5091 5.344482 -38.70039 145.1282 5.344482 -37.47573 145.1282 3.621114 -37.47573 144.5091 4.093343 -38.70039 146.544 3.516525 -38.70039 146.3776 3.516525 -37.47573 146.3776 4.093343 -37.47573 146.544 6.25433 -38.70043 156.9494 6.25433 -37.47573 156.9494 6.25433 -38.70043 155.0093 6.25433 -39.31753 155.9738 6.25433 -37.47573 155.9738 6.25433 -37.47573 155.0093 5.392851 -38.70042 155.0093 5.392851 -37.47573 155.0093 3.927212 -38.70039 150.4831 3.927212 -37.47573 150.4831 3.170327 -38.70039 151.0378 3.170327 -37.47573 151.0378 2.438744 -39.31753 155.9738 -1.103743 -39.31754 145.874 -1.103743 -37.47573 151.6167 -1.103743 -38.70039 146.3776 -1.103743 -37.47573 144.4816 -1.103743 -39.31753 155.9738 -6.925807 -39.31754 150.5315 -6.925807 -39.31754 146.8221 -7.789065 -39.31754 146.6534 -7.789065 -39.31754 152.7816 -1.103743 -39.31754 152.2433 -3.941508 -39.31754 152.1198 -4.518202 -39.31753 155.0093 -1.103743 -39.31753 155.0093 -5.800817 -39.31754 145.0054 -7.219634 -39.31754 145.5043 -6.633162 -39.31754 146.1679 -5.751792 -39.31754 145.8813 -7.281514 -39.31754 153.9384 -6.269902 -39.31753 155.0093 -5.613441 -39.31754 151.6906 -6.511563 -39.31754 151.1949 -1.103743 -39.31754 144.9852 -6.436627 -38.70039 149.8702 -6.436627 -37.47573 149.8702 -6.436627 -37.47573 146.9177 -6.436629 -38.70039 146.9177 -8.278247 -38.70039 153.8347 -8.278247 -38.70039 146.5578 -8.278247 -37.47573 146.5578 -8.278247 -37.47573 153.8347 -4.775732 -38.70043 156.9494 -4.775732 -37.47573 156.9494 -1.103743 -38.70039 151.6167 -3.806211 -37.47573 151.5133 -3.806211 -38.70039 151.5133 -5.828599 -38.70039 144.5091 -5.828599 -37.47573 144.5091 -7.551967 -37.47573 145.1282 -7.551967 -38.70039 145.1282 -6.300828 -38.70039 146.544 -6.300828 -37.47573 146.544 -5.72401 -37.47573 146.3776 -5.72401 -38.70039 146.3776 -8.461814 -38.70043 156.9494 -8.461814 -37.47573 156.9494 -8.461814 -38.70043 155.0093 -8.461814 -37.47573 155.0093 -8.461814 -37.47573 155.9738 -8.461814 -39.31753 155.9738 -7.600337 -38.70042 155.0093 -7.600337 -37.47573 155.0093 -6.134698 -38.70039 150.4831 -6.134698 -37.47573 150.4831 -1.103743 -38.70039 144.4816 -5.377812 -37.47573 151.0378 -5.377812 -38.70039 151.0378 -4.646229 -39.31753 155.9738 10.9723 -41.53192 173.8982 10.9723 -39.45044 176.007 10.9723 -41.53192 164.6898 10.9723 -41.53192 169.2228 -17.64937 0 130.6999 -16.59355 0 129.6871 -18.75353 0 158.2004 -19.01404 0 164.6898 10.9723 0 176.007 -19.01403 0 173.8982 -19.01404 0 170.3869 -18.80021 0 159.3646 -15.69215 0 176.007 38.53815 -35.26818 129.6871 37.71501 -37.73759 129.6871 35.2456 -38.56072 129.6871 36.47788 -39.45044 176.007 38.4318 -39.0051 176.007 38.87714 -37.05117 176.007 35.451 -39.63248 130.6999 36.81567 -41.53192 164.6898 39.59397 -35.48951 130.6999 40.95864 -37.38895 164.6898 36.81566 -41.53192 173.8982 40.95863 -37.38895 173.8982 38.55823 -38.59674 130.6999 39.9229 -40.49618 164.6898 39.92289 -40.49618 173.8982 36.73121 -41.01155 175.4798 40.43826 -37.30451 175.4798 39.55012 -40.12341 175.4798 36.13555 -25.83975 129.6871 36.13554 -5.731884 129.6871 38.53815 -25.83975 129.6871 39.59397 -25.83975 130.6999 40.6981 -25.83975 158.2004 38.53815 -5.731884 129.6871 39.59397 -5.731883 130.6999 40.6981 -5.731882 158.2004 40.76041 -7.284054 159.7526 40.76041 -24.28758 159.7526 40.74483 -25.4517 159.3645 40.74483 -6.119925 159.3645 36.13555 -5.731883 158.2004 36.13555 -6.119926 159.3645 36.13555 -7.284054 159.7526 36.13555 -25.83975 158.2004 36.13555 -25.4517 159.3645 36.13555 -24.28758 159.7526 15.68362 -36.31864 129.6871 30.45106 -36.31864 129.6871 15.68362 -38.56072 129.6871 15.68362 -39.63248 130.6999 15.68362 -41.16928 158.2004 30.45106 -38.56072 129.6871 30.45106 -39.63248 130.6999 30.45106 -41.16928 158.2004 28.89889 -41.25602 159.7526 17.23579 -41.25602 159.7526 16.07166 -41.23434 159.3645 30.06302 -41.23434 159.3645 28.89889 -36.31864 159.7526 30.06302 -36.31864 159.3645 30.45106 -36.31864 158.2004 15.68362 -36.31865 158.2004 16.07166 -36.31865 159.3645 17.23579 -36.31865 159.7526 37.63675 -5.731886 176.007 37.63675 -25.83975 176.007 40.95863 -25.83975 173.8982 40.43826 -25.83975 175.4798 38.87714 -25.83975 176.007 40.95864 -25.83975 170.3869 40.95863 -5.731886 173.8982 40.95864 -5.731886 170.3869 40.43826 -5.731886 175.4798 38.87714 -5.731886 176.007 40.95864 -24.28758 168.8348 40.95864 -7.284057 168.8348 40.95864 -25.4517 169.2228 40.95864 -6.119928 169.2228 37.63675 -5.731886 170.3869 37.63675 -6.119929 169.2228 37.63675 -7.284058 168.8348 37.63675 -24.28758 168.8348 37.63675 -25.45171 169.2228 37.63675 -25.83975 170.3869 30.45106 -38.14337 176.007 15.68362 -38.14337 176.007 15.68362 -39.45044 176.007 15.68362 -41.53192 173.8982 15.68362 -41.01155 175.4798 15.68362 -41.53192 170.3869 30.45106 -41.01155 175.4798 30.45106 -41.53192 173.8982 30.45106 -41.53192 170.3869 30.45106 -39.45044 176.007 17.23579 -41.53192 168.8348 28.89889 -41.53192 168.8348 16.07166 -41.53192 169.2228 30.06302 -41.53192 169.2228 28.89889 -38.14337 168.8348 30.06302 -38.14337 169.2228 17.23579 -38.14337 168.8348 16.07166 -38.14337 169.2228 15.68362 -38.14337 170.3869 30.45106 -38.14337 170.3869 40.95864 -7.312862 164.6898 40.95864 -24.281 164.6898 40.95864 -25.4423 164.6898 40.95864 -6.15367 164.6898 40.95864 -37.38895 170.3869 39.92289 -40.49618 170.3869 36.81566 -41.53192 170.3869 40.95864 -37.38895 169.2228 39.92289 -40.49618 169.2228 36.81566 -41.53192 169.2228 28.97055 -41.53192 164.6898 30.14089 -41.53192 164.6898 36.60186 -41.23434 159.3645 39.70909 -40.1986 159.3645 40.74483 -37.09137 159.3645 40.6981 -37.02631 158.2004 39.66235 -40.13354 158.2004 36.55513 -41.16928 158.2004 17.30745 -41.53192 164.6898 16.14953 -41.53192 164.6898 38.87714 0 176.007 40.43826 0 175.4798 40.95864 0 169.2228 23.04834 -38.70043 156.9494 23.04834 -37.47573 156.9494 23.04834 -37.47573 146.3776 17.22628 -39.31754 150.5315 16.36302 -39.31754 152.7816 16.36302 -39.31754 146.6534 17.22628 -39.31754 146.8221 19.63388 -39.31753 155.0093 20.21058 -39.31754 152.1198 18.35127 -39.31754 145.0054 18.40029 -39.31754 145.8813 17.51892 -39.31754 146.1679 16.93245 -39.31754 145.5043 16.87057 -39.31754 153.9384 17.64052 -39.31754 151.1949 18.53864 -39.31754 151.6906 17.88218 -39.31753 155.0093 17.71546 -38.70039 149.8702 17.71546 -38.70039 146.9177 17.71546 -37.47573 146.9177 17.71546 -37.47573 149.8702 15.87384 -38.70039 153.8347 15.87384 -37.47573 153.8347 15.87384 -37.47573 146.5578 15.87384 -38.70039 146.5578 19.37635 -38.70043 156.9494 19.37635 -37.47573 156.9494 20.34587 -38.70039 151.5133 20.34587 -37.47573 151.5133 18.32349 -38.70039 144.5091 16.60012 -38.70039 145.1282 16.60012 -37.47573 145.1282 18.32349 -37.47573 144.5091 17.85126 -38.70039 146.544 18.42807 -38.70039 146.3776 18.42807 -37.47573 146.3776 17.85126 -37.47573 146.544 15.69027 -38.70043 156.9494 15.69027 -37.47573 156.9494 15.69027 -38.70043 155.0093 15.69027 -39.31753 155.9738 15.69027 -37.47573 155.9738 15.69027 -37.47573 155.0093 16.55175 -38.70042 155.0093 16.55175 -37.47573 155.0093 18.01739 -38.70039 150.4831 18.01739 -37.47573 150.4831 18.77427 -38.70039 151.0378 18.77427 -37.47573 151.0378 19.50586 -39.31753 155.9738 23.04834 -39.31754 145.874 23.04834 -37.47573 151.6167 23.04834 -38.70039 146.3776 23.04834 -37.47573 144.4816 23.04834 -39.31753 155.9738 28.87041 -39.31754 150.5315 28.87041 -39.31754 146.8221 29.73366 -39.31754 146.6534 29.73366 -39.31754 152.7816 23.04834 -39.31754 152.2433 25.88611 -39.31754 152.1198 26.4628 -39.31753 155.0093 23.04834 -39.31753 155.0093 27.74542 -39.31754 145.0054 29.16423 -39.31754 145.5043 28.57776 -39.31754 146.1679 27.69639 -39.31754 145.8813 29.22611 -39.31754 153.9384 28.2145 -39.31753 155.0093 27.55804 -39.31754 151.6906 28.45616 -39.31754 151.1949 23.04834 -39.31754 144.9852 28.38123 -38.70039 149.8702 28.38123 -37.47573 149.8702 28.38123 -37.47573 146.9177 28.38123 -38.70039 146.9177 30.22285 -38.70039 153.8347 30.22285 -38.70039 146.5578 30.22285 -37.47573 146.5578 30.22285 -37.47573 153.8347 26.72033 -38.70043 156.9494 26.72033 -37.47573 156.9494 23.04834 -38.70039 151.6167 25.75081 -37.47573 151.5133 25.75081 -38.70039 151.5133 27.7732 -38.70039 144.5091 27.7732 -37.47573 144.5091 29.49657 -37.47573 145.1282 29.49657 -38.70039 145.1282 28.24543 -38.70039 146.544 28.24543 -37.47573 146.544 27.66861 -37.47573 146.3776 27.66861 -38.70039 146.3776 30.40641 -38.70043 156.9494 30.40641 -37.47573 156.9494 30.40641 -38.70043 155.0093 30.40641 -37.47573 155.0093 30.40641 -37.47573 155.9738 30.40641 -39.31753 155.9738 29.54494 -38.70042 155.0093 29.54494 -37.47573 155.0093 28.0793 -38.70039 150.4831 28.0793 -37.47573 150.4831 23.04834 -38.70039 144.4816 27.32241 -37.47573 151.0378 27.32241 -38.70039 151.0378 26.59083 -39.31753 155.9738 39.59397 0 130.6999 38.53815 0 129.6871 40.69812 0 158.2004 40.95864 0 164.6898 40.95863 0 173.8982 40.95864 0 170.3869 40.74481 0 159.3646 37.63675 0 176.007 -16.59355 35.26818 129.6871 -15.77042 37.73759 129.6871 -13.301 38.56072 129.6871 -14.53328 39.45044 176.007 -16.4872 39.0051 176.007 -16.93254 37.05117 176.007 -13.5064 39.63248 130.6999 -14.87107 41.53192 164.6898 -17.64937 35.48951 130.6999 -19.01404 37.38895 164.6898 -14.87106 41.53192 173.8982 -19.01403 37.38895 173.8982 -16.61363 38.59674 130.6999 -17.9783 40.49618 164.6898 -17.9783 40.49618 173.8982 -14.78662 41.01155 175.4798 -18.49366 37.30451 175.4798 -17.60552 40.12341 175.4798 -14.19095 25.83975 129.6871 -14.19095 5.731884 129.6871 -16.59355 25.83975 129.6871 -17.64937 25.83975 130.6999 -18.7535 25.83975 158.2004 -16.59355 5.731884 129.6871 -17.64937 5.731883 130.6999 -18.7535 5.731882 158.2004 -18.81582 7.284054 159.7526 -18.81582 24.28758 159.7526 -18.80024 25.4517 159.3645 -18.80024 6.119925 159.3645 -14.19095 5.731883 158.2004 -14.19095 6.119926 159.3645 -14.19095 7.284054 159.7526 -14.19095 25.83975 158.2004 -14.19095 25.4517 159.3645 -14.19095 24.28758 159.7526 6.260982 36.31864 129.6871 -8.506463 36.31864 129.6871 6.260982 38.56072 129.6871 6.260982 39.63248 130.6999 6.260982 41.16928 158.2004 -8.506463 38.56072 129.6871 -8.506463 39.63248 130.6999 -8.506463 41.16928 158.2004 -6.954289 41.25602 159.7526 4.708811 41.25602 159.7526 5.872938 41.23434 159.3645 -8.118418 41.23434 159.3645 -6.954289 36.31864 159.7526 -8.118418 36.31864 159.3645 -8.506463 36.31864 158.2004 6.260982 36.31865 158.2004 5.872939 36.31865 159.3645 4.708812 36.31865 159.7526 -15.69215 5.731886 176.007 -15.69216 25.83975 176.007 -19.01403 25.83975 173.8982 -18.49366 25.83975 175.4798 -16.93254 25.83975 176.007 -19.01404 25.83975 170.3869 -19.01403 5.731886 173.8982 -19.01404 5.731886 170.3869 -18.49366 5.731886 175.4798 -16.93254 5.731886 176.007 -19.01404 24.28758 168.8348 -19.01404 7.284057 168.8348 -19.01404 25.4517 169.2228 -19.01404 6.119928 169.2228 -15.69215 5.731886 170.3869 -15.69215 6.119929 169.2228 -15.69215 7.284058 168.8348 -15.69216 24.28758 168.8348 -15.69216 25.45171 169.2228 -15.69216 25.83975 170.3869 -8.506463 38.14337 176.007 6.260979 38.14337 176.007 6.260979 39.45044 176.007 6.260978 41.53192 173.8982 6.260978 41.01155 175.4798 6.260978 41.53192 170.3869 -8.506463 41.01155 175.4798 -8.506463 41.53192 173.8982 -8.506463 41.53192 170.3869 -8.506463 39.45044 176.007 4.708808 41.53192 168.8348 -6.95429 41.53192 168.8348 5.872935 41.53192 169.2228 -8.118418 41.53192 169.2228 -6.95429 38.14337 168.8348 -8.118418 38.14337 169.2228 4.708808 38.14337 168.8348 5.872935 38.14337 169.2228 6.260979 38.14337 170.3869 -8.506463 38.14337 170.3869 -19.01404 7.312862 164.6898 -19.01404 24.281 164.6898 -19.01404 25.4423 164.6898 -19.01404 6.15367 164.6898 -19.01404 37.38895 170.3869 -17.9783 40.49618 170.3869 -14.87106 41.53192 170.3869 -19.01404 37.38895 169.2228 -17.9783 40.49618 169.2228 -14.87106 41.53192 169.2228 -7.025946 41.53192 164.6898 -8.196288 41.53192 164.6898 -14.65726 41.23434 159.3645 -17.76449 40.1986 159.3645 -18.80024 37.09137 159.3645 -18.7535 37.02631 158.2004 -17.71776 40.13354 158.2004 -14.61053 41.16928 158.2004 4.637153 41.53192 164.6898 5.795067 41.53192 164.6898 10.9723 41.16927 158.2004 10.9723 37.03272 176.007 10.9723 38.56072 129.6871 10.9723 39.63248 130.6999 10.9723 41.01155 175.4798 10.9723 41.23437 159.3646 10.9723 41.53192 170.3869 -1.103744 38.70043 156.9494 -1.103744 37.47573 156.9494 -1.103744 37.47573 146.3776 4.718321 39.31754 150.5315 5.58158 39.31754 152.7816 5.58158 39.31754 146.6534 4.718321 39.31754 146.8221 2.310717 39.31753 155.0093 1.734023 39.31754 152.1198 3.593331 39.31754 145.0054 3.544306 39.31754 145.8813 4.425676 39.31754 146.1679 5.012147 39.31754 145.5043 5.074027 39.31754 153.9384 4.304078 39.31754 151.1949 3.405955 39.31754 151.6906 4.062415 39.31753 155.0093 4.229141 38.70039 149.8702 4.229142 38.70039 146.9177 4.229141 37.47573 146.9177 4.229141 37.47573 149.8702 6.070761 38.70039 153.8347 6.070761 37.47573 153.8347 6.070761 37.47573 146.5578 6.070761 38.70039 146.5578 2.568246 38.70043 156.9494 2.568246 37.47573 156.9494 1.598725 38.70039 151.5133 1.598725 37.47573 151.5133 3.621113 38.70039 144.5091 5.344481 38.70039 145.1282 5.344481 37.47573 145.1282 3.621113 37.47573 144.5091 4.093342 38.70039 146.544 3.516524 38.70039 146.3776 3.516524 37.47573 146.3776 4.093342 37.47573 146.544 6.254329 38.70043 156.9494 6.254329 37.47573 156.9494 6.254329 38.70043 155.0093 6.254329 39.31753 155.9738 6.254329 37.47573 155.9738 6.254329 37.47573 155.0093 5.39285 38.70042 155.0093 5.39285 37.47573 155.0093 3.927211 38.70039 150.4831 3.927211 37.47573 150.4831 3.170326 38.70039 151.0378 3.170326 37.47573 151.0378 2.438743 39.31753 155.9738 -1.103744 39.31754 145.874 -1.103744 37.47573 151.6167 -1.103744 38.70039 146.3776 -1.103744 37.47573 144.4816 -1.103744 39.31753 155.9738 -6.925808 39.31754 150.5315 -6.925808 39.31754 146.8221 -7.789066 39.31754 146.6534 -7.789066 39.31754 152.7816 -1.103744 39.31754 152.2433 -3.941509 39.31754 152.1198 -4.518203 39.31753 155.0093 -1.103744 39.31753 155.0093 -5.800818 39.31754 145.0054 -7.219635 39.31754 145.5043 -6.633163 39.31754 146.1679 -5.751793 39.31754 145.8813 -7.281515 39.31754 153.9384 -6.269903 39.31753 155.0093 -5.613442 39.31754 151.6906 -6.511564 39.31754 151.1949 -1.103744 39.31754 144.9852 -6.436628 38.70039 149.8702 -6.436628 37.47573 149.8702 -6.436628 37.47573 146.9177 -6.43663 38.70039 146.9177 -8.278248 38.70039 153.8347 -8.278248 38.70039 146.5578 -8.278248 37.47573 146.5578 -8.278248 37.47573 153.8347 -4.775733 38.70043 156.9494 -4.775733 37.47573 156.9494 -1.103744 38.70039 151.6167 -3.806212 37.47573 151.5133 -3.806212 38.70039 151.5133 -5.8286 38.70039 144.5091 -5.8286 37.47573 144.5091 -7.551968 37.47573 145.1282 -7.551968 38.70039 145.1282 -6.300829 38.70039 146.544 -6.300829 37.47573 146.544 -5.724011 37.47573 146.3776 -5.724011 38.70039 146.3776 -8.461815 38.70043 156.9494 -8.461815 37.47573 156.9494 -8.461815 38.70043 155.0093 -8.461815 37.47573 155.0093 -8.461815 37.47573 155.9738 -8.461815 39.31753 155.9738 -7.600338 38.70042 155.0093 -7.600338 37.47573 155.0093 -6.134699 38.70039 150.4831 -6.134699 37.47573 150.4831 -1.103744 38.70039 144.4816 -5.377813 37.47573 151.0378 -5.377813 38.70039 151.0378 -4.64623 39.31753 155.9738 10.9723 41.53192 173.8982 10.9723 39.45044 176.007 10.9723 41.53192 164.6898 10.9723 41.53192 169.2228 38.53815 35.26818 129.6871 37.71501 37.73759 129.6871 35.2456 38.56072 129.6871 36.47788 39.45044 176.007 38.4318 39.0051 176.007 38.87714 37.05117 176.007 35.451 39.63248 130.6999 36.81567 41.53192 164.6898 39.59397 35.48951 130.6999 40.95864 37.38895 164.6898 36.81566 41.53192 173.8982 40.95863 37.38895 173.8982 38.55823 38.59674 130.6999 39.9229 40.49618 164.6898 39.92289 40.49618 173.8982 36.73121 41.01155 175.4798 40.43826 37.30451 175.4798 39.55012 40.12341 175.4798 36.13555 25.83975 129.6871 36.13554 5.731884 129.6871 38.53815 25.83975 129.6871 39.59397 25.83975 130.6999 40.6981 25.83975 158.2004 38.53815 5.731884 129.6871 39.59397 5.731883 130.6999 40.6981 5.731882 158.2004 40.76041 7.284054 159.7526 40.76041 24.28758 159.7526 40.74483 25.4517 159.3645 40.74483 6.119925 159.3645 36.13555 5.731883 158.2004 36.13555 6.119926 159.3645 36.13555 7.284054 159.7526 36.13555 25.83975 158.2004 36.13555 25.4517 159.3645 36.13555 24.28758 159.7526 15.68362 36.31864 129.6871 30.45106 36.31864 129.6871 15.68362 38.56072 129.6871 15.68362 39.63248 130.6999 15.68362 41.16928 158.2004 30.45106 38.56072 129.6871 30.45106 39.63248 130.6999 30.45106 41.16928 158.2004 28.89889 41.25602 159.7526 17.23579 41.25602 159.7526 16.07166 41.23434 159.3645 30.06302 41.23434 159.3645 28.89889 36.31864 159.7526 30.06302 36.31864 159.3645 30.45106 36.31864 158.2004 15.68362 36.31865 158.2004 16.07166 36.31865 159.3645 17.23579 36.31865 159.7526 37.63675 5.731886 176.007 37.63675 25.83975 176.007 40.95863 25.83975 173.8982 40.43826 25.83975 175.4798 38.87714 25.83975 176.007 40.95864 25.83975 170.3869 40.95863 5.731886 173.8982 40.95864 5.731886 170.3869 40.43826 5.731886 175.4798 38.87714 5.731886 176.007 40.95864 24.28758 168.8348 40.95864 7.284057 168.8348 40.95864 25.4517 169.2228 40.95864 6.119928 169.2228 37.63675 5.731886 170.3869 37.63675 6.119929 169.2228 37.63675 7.284058 168.8348 37.63675 24.28758 168.8348 37.63675 25.45171 169.2228 37.63675 25.83975 170.3869 30.45106 38.14337 176.007 15.68362 38.14337 176.007 15.68362 39.45044 176.007 15.68362 41.53192 173.8982 15.68362 41.01155 175.4798 15.68362 41.53192 170.3869 30.45106 41.01155 175.4798 30.45106 41.53192 173.8982 30.45106 41.53192 170.3869 30.45106 39.45044 176.007 17.23579 41.53192 168.8348 28.89889 41.53192 168.8348 16.07166 41.53192 169.2228 30.06302 41.53192 169.2228 28.89889 38.14337 168.8348 30.06302 38.14337 169.2228 17.23579 38.14337 168.8348 16.07166 38.14337 169.2228 15.68362 38.14337 170.3869 30.45106 38.14337 170.3869 40.95864 7.312862 164.6898 40.95864 24.281 164.6898 40.95864 25.4423 164.6898 40.95864 6.15367 164.6898 40.95864 37.38895 170.3869 39.92289 40.49618 170.3869 36.81566 41.53192 170.3869 40.95864 37.38895 169.2228 39.92289 40.49618 169.2228 36.81566 41.53192 169.2228 28.97054 41.53192 164.6898 30.14089 41.53192 164.6898 36.60186 41.23434 159.3645 39.70909 40.1986 159.3645 40.74483 37.09137 159.3645 40.6981 37.02631 158.2004 39.66235 40.13354 158.2004 36.55513 41.16928 158.2004 17.30745 41.53192 164.6898 16.14953 41.53192 164.6898 23.04834 38.70043 156.9494 23.04834 37.47573 156.9494 23.04834 37.47573 146.3776 17.22628 39.31754 150.5315 16.36302 39.31754 152.7816 16.36302 39.31754 146.6534 17.22628 39.31754 146.8221 19.63388 39.31753 155.0093 20.21058 39.31754 152.1198 18.35127 39.31754 145.0054 18.40029 39.31754 145.8813 17.51892 39.31754 146.1679 16.93245 39.31754 145.5043 16.87057 39.31754 153.9384 17.64052 39.31754 151.1949 18.53864 39.31754 151.6906 17.88218 39.31753 155.0093 17.71546 38.70039 149.8702 17.71545 38.70039 146.9177 17.71546 37.47573 146.9177 17.71546 37.47573 149.8702 15.87384 38.70039 153.8347 15.87384 37.47573 153.8347 15.87384 37.47573 146.5578 15.87384 38.70039 146.5578 19.37635 38.70043 156.9494 19.37635 37.47573 156.9494 20.34587 38.70039 151.5133 20.34587 37.47573 151.5133 18.32348 38.70039 144.5091 16.60012 38.70039 145.1282 16.60012 37.47573 145.1282 18.32348 37.47573 144.5091 17.85126 38.70039 146.544 18.42807 38.70039 146.3776 18.42807 37.47573 146.3776 17.85126 37.47573 146.544 15.69027 38.70043 156.9494 15.69027 37.47573 156.9494 15.69027 38.70043 155.0093 15.69027 39.31753 155.9738 15.69027 37.47573 155.9738 15.69027 37.47573 155.0093 16.55175 38.70042 155.0093 16.55175 37.47573 155.0093 18.01739 38.70039 150.4831 18.01739 37.47573 150.4831 18.77427 38.70039 151.0378 18.77427 37.47573 151.0378 19.50586 39.31753 155.9738 23.04834 39.31754 145.874 23.04834 37.47573 151.6167 23.04834 38.70039 146.3776 23.04834 37.47573 144.4816 23.04834 39.31753 155.9738 28.87041 39.31754 150.5315 28.87041 39.31754 146.8221 29.73366 39.31754 146.6534 29.73366 39.31754 152.7816 23.04834 39.31754 152.2433 25.88611 39.31754 152.1198 26.4628 39.31753 155.0093 23.04834 39.31753 155.0093 27.74542 39.31754 145.0054 29.16423 39.31754 145.5043 28.57776 39.31754 146.1679 27.69639 39.31754 145.8813 29.22611 39.31754 153.9384 28.2145 39.31753 155.0093 27.55804 39.31754 151.6906 28.45616 39.31754 151.1949 23.04834 39.31754 144.9852 28.38123 38.70039 149.8702 28.38123 37.47573 149.8702 28.38123 37.47573 146.9177 28.38123 38.70039 146.9177 30.22285 38.70039 153.8347 30.22285 38.70039 146.5578 30.22285 37.47573 146.5578 30.22285 37.47573 153.8347 26.72033 38.70043 156.9494 26.72033 37.47573 156.9494 23.04834 38.70039 151.6167 25.75081 37.47573 151.5133 25.75081 38.70039 151.5133 27.7732 38.70039 144.5091 27.7732 37.47573 144.5091 29.49657 37.47573 145.1282 29.49657 38.70039 145.1282 28.24543 38.70039 146.544 28.24543 37.47573 146.544 27.66861 37.47573 146.3776 27.66861 38.70039 146.3776 30.40641 38.70043 156.9494 30.40641 37.47573 156.9494 30.40641 38.70043 155.0093 30.40641 37.47573 155.0093 30.40641 37.47573 155.9738 30.40641 39.31753 155.9738 29.54494 38.70042 155.0093 29.54494 37.47573 155.0093 28.0793 38.70039 150.4831 28.0793 37.47573 150.4831 23.04834 38.70039 144.4816 27.32241 37.47573 151.0378 27.32241 38.70039 151.0378 26.59083 39.31753 155.9738 -37.35448 -28.4024 157.2454 -37.35448 -31.58863 153.2378 -37.35448 -29.80026 130.1495 -37.35448 -29.31087 129.6872 -37.35448 -31.58863 149.873 -37.35448 0 157.2454 -37.35448 -29.42375 153.5353 -37.35448 -30.78969 147.8021 -37.35448 -30.90577 149.873 -53.00191 0 157.2454 -52.35549 0 130.1504 -53.10922 0 147.3571 -56.17117 0 149.873 -56.17117 0 153.2378 -55.44563 0 149.873 -54.0526 0 153.5353 -51.86 0 129.6871 -55.3561 0 147.8021 -52.81626 -28.21675 157.2454 -52.25931 -28.4024 157.2454 -53.00191 -27.6598 157.2454 -52.35549 -4.752643 130.1504 -53.10922 -3.079486 147.3571 -56.17117 -30.84603 149.873 -56.17117 -30.84603 153.2378 -55.44563 -30.16317 149.873 -53.31 -29.42375 153.5353 -55.42857 -31.58863 153.2378 -41.01063 -29.42375 153.5353 -48.92695 -29.42375 153.5353 -54.05259 -28.68115 153.5353 -53.35078 -29.31087 129.6872 -53.83423 -29.80026 130.1495 -54.61351 -30.78969 147.8021 -54.70303 -30.90577 149.873 -55.35611 -20.51354 147.8021 -54.57683 -22.25408 130.1495 -54.57683 -29.05766 130.1495 -55.35611 -30.04709 147.8021 -53.10924 -13.96375 147.3573 -52.35374 -12.26866 130.1486 -52.35374 -21.75667 130.1486 -53.10924 -20.06158 147.3573 -55.35611 -3.532016 147.8021 -54.57683 -5.250237 130.1495 -54.57683 -11.77126 130.1495 -55.3561 -13.51179 147.8021 -54.09337 -22.30204 129.6872 -54.09337 -28.56827 129.6872 -51.86001 -12.23048 129.6873 -51.86001 -21.79485 129.6873 -54.09337 -5.291624 129.6872 -54.09337 -11.72329 129.6872 -51.86 -4.799234 129.6871 -55.42857 -31.58863 149.873 -41.01063 -26.99314 153.5353 -41.52228 -26.99314 155.817 -48.39953 -26.99314 155.817 -48.92695 -26.99314 153.5353 -48.39953 -28.79562 155.817 -41.52228 -28.79562 155.817 -55.17046 -30.60404 147.8021 -55.25998 -30.72012 149.873 -55.98553 -31.40298 153.2378 -55.98553 -31.40298 149.873 -53.86694 -29.2381 153.5353 -54.39118 -29.61461 130.1495 -53.90773 -29.12522 129.6872 -21.70705 0 157.2454 -22.35346 0 130.1504 -21.59973 0 147.3571 -18.53778 0 149.873 -18.53778 0 153.2378 -19.26332 0 149.873 -20.65636 0 153.5353 -22.84895 0 129.6871 -19.35285 0 147.8021 -21.8927 -28.21675 157.2454 -22.44964 -28.4024 157.2454 -21.70705 -27.6598 157.2454 -22.35346 -4.752643 130.1504 -21.59973 -3.079486 147.3571 -18.53778 -30.84603 149.873 -18.53778 -30.84603 153.2378 -19.26332 -30.16317 149.873 -21.39895 -29.42375 153.5353 -19.28038 -31.58863 153.2378 -33.69832 -29.42375 153.5353 -25.782 -29.42375 153.5353 -20.65636 -28.68115 153.5353 -21.35818 -29.31087 129.6872 -20.87472 -29.80026 130.1495 -20.09544 -30.78969 147.8021 -20.00592 -30.90577 149.873 -19.35284 -20.51354 147.8021 -20.13212 -22.25408 130.1495 -20.13212 -29.05766 130.1495 -19.35284 -30.04709 147.8021 -21.59972 -13.96375 147.3573 -22.35522 -12.26866 130.1486 -22.35522 -21.75667 130.1486 -21.59972 -20.06158 147.3573 -19.35284 -3.532016 147.8021 -20.13212 -5.250237 130.1495 -20.13212 -11.77126 130.1495 -19.35285 -13.51179 147.8021 -20.61558 -22.30204 129.6872 -20.61558 -28.56827 129.6872 -22.84894 -12.23048 129.6873 -22.84894 -21.79485 129.6873 -20.61558 -5.291624 129.6872 -20.61558 -11.72329 129.6872 -22.84895 -4.799234 129.6871 -19.28038 -31.58863 149.873 -33.69832 -26.99314 153.5353 -33.18667 -26.99314 155.817 -26.30943 -26.99314 155.817 -25.782 -26.99314 153.5353 -26.30943 -28.79562 155.817 -33.18667 -28.79562 155.817 -19.53849 -30.60404 147.8021 -19.44898 -30.72012 149.873 -18.72343 -31.40298 153.2378 -18.72343 -31.40298 149.873 -20.84201 -29.2381 153.5353 -20.31777 -29.61461 130.1495 -20.80123 -29.12522 129.6872 -37.35448 28.4024 157.2454 -37.35448 31.58863 153.2378 -37.35448 29.80026 130.1495 -37.35448 29.31087 129.6872 -37.35448 31.58863 149.873 -37.35448 29.42375 153.5353 -37.35448 30.78969 147.8021 -37.35448 30.90577 149.873 -52.81626 28.21675 157.2454 -52.25931 28.4024 157.2454 -53.00191 27.6598 157.2454 -52.35549 4.752643 130.1504 -53.10922 3.079486 147.3571 -56.17117 30.84603 149.873 -56.17117 30.84603 153.2378 -55.44563 30.16317 149.873 -53.31 29.42375 153.5353 -55.42857 31.58863 153.2378 -41.01063 29.42375 153.5353 -48.92695 29.42375 153.5353 -54.05259 28.68115 153.5353 -53.35078 29.31087 129.6872 -53.83423 29.80026 130.1495 -54.61351 30.78969 147.8021 -54.70303 30.90577 149.873 -55.35611 20.51354 147.8021 -54.57683 22.25408 130.1495 -54.57683 29.05766 130.1495 -55.35611 30.04709 147.8021 -53.10924 13.96375 147.3573 -52.35374 12.26866 130.1486 -52.35374 21.75667 130.1486 -53.10924 20.06158 147.3573 -55.35611 3.532016 147.8021 -54.57683 5.250237 130.1495 -54.57683 11.77126 130.1495 -55.3561 13.51179 147.8021 -54.09337 22.30204 129.6872 -54.09337 28.56827 129.6872 -51.86001 12.23048 129.6873 -51.86001 21.79485 129.6873 -54.09337 5.291624 129.6872 -54.09337 11.72329 129.6872 -51.86 4.799234 129.6871 -55.42857 31.58863 149.873 -41.01063 26.99314 153.5353 -41.52228 26.99314 155.817 -48.39953 26.99314 155.817 -48.92695 26.99314 153.5353 -48.39953 28.79562 155.817 -41.52228 28.79562 155.817 -55.17046 30.60404 147.8021 -55.25998 30.72012 149.873 -55.98553 31.40298 153.2378 -55.98553 31.40298 149.873 -53.86694 29.2381 153.5353 -54.39118 29.61461 130.1495 -53.90773 29.12522 129.6872 -21.8927 28.21675 157.2454 -22.44964 28.4024 157.2454 -21.70705 27.6598 157.2454 -22.35346 4.752643 130.1504 -21.59973 3.079486 147.3571 -18.53778 30.84603 149.873 -18.53778 30.84603 153.2378 -19.26332 30.16317 149.873 -21.39895 29.42375 153.5353 -19.28038 31.58863 153.2378 -33.69832 29.42375 153.5353 -25.782 29.42375 153.5353 -20.65636 28.68115 153.5353 -21.35818 29.31087 129.6872 -20.87472 29.80026 130.1495 -20.09544 30.78969 147.8021 -20.00592 30.90577 149.873 -19.35284 20.51354 147.8021 -20.13212 22.25408 130.1495 -20.13212 29.05766 130.1495 -19.35284 30.04709 147.8021 -21.59972 13.96375 147.3573 -22.35522 12.26866 130.1486 -22.35522 21.75667 130.1486 -21.59972 20.06158 147.3573 -19.35284 3.532016 147.8021 -20.13212 5.250237 130.1495 -20.13212 11.77126 130.1495 -19.35285 13.51179 147.8021 -20.61558 22.30204 129.6872 -20.61558 28.56827 129.6872 -22.84894 12.23048 129.6873 -22.84894 21.79485 129.6873 -20.61558 5.291624 129.6872 -20.61558 11.72329 129.6872 -22.84895 4.799234 129.6871 -19.28038 31.58863 149.873 -33.69832 26.99314 153.5353 -33.18667 26.99314 155.817 -26.30943 26.99314 155.817 -25.782 26.99314 153.5353 -26.30943 28.79562 155.817 -33.18667 28.79562 155.817 -19.53849 30.60404 147.8021 -19.44898 30.72012 149.873 -18.72343 31.40298 153.2378 -18.72343 31.40298 149.873 -20.84201 29.2381 153.5353 -20.31777 29.61461 130.1495 -20.80123 29.12522 129.6872 - + - - --0.159831 -0.985228 -0.061474 --0.705588 -0.705376 -0.067746 --0.705588 -0.705377 -0.067746 --0.705588 -0.705377 -0.067746 --0.159831 -0.985228 -0.061474 --0.159831 -0.985228 -0.061474 --0.987087 -0.160182 0.000001 --0.707107 -0.707107 0.000000 --0.700073 -0.696893 0.155683 --0.700073 -0.696893 0.155683 --0.974743 -0.158179 0.157659 --0.987087 -0.160182 0.000001 --0.705588 -0.705377 -0.067746 --0.705588 -0.705376 -0.067746 --0.985934 -0.159934 -0.048521 --0.985934 -0.159934 -0.048521 --0.985934 -0.159934 -0.048521 --0.705588 -0.705377 -0.067746 --0.707107 -0.707107 0.000000 --0.160182 -0.987087 0.000000 --0.155746 -0.975487 0.155460 --0.155746 -0.975487 0.155460 --0.700073 -0.696893 0.155683 --0.707107 -0.707107 0.000000 --0.155928 -0.141040 0.977647 --0.541660 -0.532699 0.650258 --0.107470 -0.721820 0.683686 --0.107470 -0.721820 0.683686 --0.018551 -0.170483 0.985186 --0.155928 -0.141040 0.977647 --0.173478 -0.024209 0.984540 --0.720099 -0.114166 0.684415 --0.541660 -0.532699 0.650258 --0.541660 -0.532699 0.650258 --0.155928 -0.141040 0.977647 --0.173478 -0.024209 0.984540 --0.541660 -0.532699 0.650258 --0.700073 -0.696893 0.155683 --0.155746 -0.975487 0.155460 --0.155746 -0.975487 0.155460 --0.107470 -0.721820 0.683686 --0.541660 -0.532699 0.650258 --0.720099 -0.114166 0.684415 --0.974743 -0.158179 0.157659 --0.700073 -0.696893 0.155683 --0.700073 -0.696893 0.155683 --0.541660 -0.532699 0.650258 --0.720099 -0.114166 0.684415 --0.902713 -0.144766 -0.405157 --0.676471 -0.107125 -0.728637 --0.456612 -0.453865 -0.765188 --0.456612 -0.453865 -0.765188 --0.645117 -0.643053 -0.412683 --0.902713 -0.144766 -0.405157 --0.456612 -0.453865 -0.765188 --0.107386 -0.671902 -0.732814 --0.144762 -0.898824 -0.413714 --0.144762 -0.898824 -0.413714 --0.645117 -0.643053 -0.412683 --0.456612 -0.453865 -0.765188 --0.676471 -0.107125 -0.728637 --0.902713 -0.144766 -0.405157 --0.911793 0.000000 -0.410650 --0.911793 0.000000 -0.410650 --0.692241 0.000000 -0.721666 --0.676471 -0.107125 -0.728637 --0.911793 0.000000 -0.410650 --0.692242 0.000000 -0.721666 --0.692241 0.000000 -0.721666 --0.692241 0.000000 -0.721666 --0.911793 0.000000 -0.410650 --0.911793 0.000000 -0.410650 -0.000000 0.987088 -0.160182 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.987088 -0.160182 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.987088 -0.160182 -0.000000 1.000000 0.000000 -0.000000 0.986432 -0.164170 -0.000000 0.986432 -0.164170 -0.000000 0.701326 -0.712841 -0.000000 0.707108 -0.707105 -0.000000 0.707108 -0.707105 -0.000000 0.987088 -0.160182 -0.000000 0.986432 -0.164170 -0.000000 0.701326 -0.712841 -0.000000 0.159534 -0.987192 -0.000000 0.160184 -0.987087 -0.000000 0.160184 -0.987087 -0.000000 0.707108 -0.707105 -0.000000 0.701326 -0.712841 -0.000000 0.159534 -0.987192 --0.000000 -0.159534 -0.987193 --0.000000 -0.160184 -0.987087 --0.000000 -0.160184 -0.987087 -0.000000 0.160184 -0.987087 -0.000000 0.159534 -0.987192 --0.000000 -0.160184 -0.987087 --0.000000 -0.159534 -0.987193 --0.000000 -0.701324 -0.712842 --0.000000 -0.701324 -0.712842 --0.000000 -0.707107 -0.707106 --0.000000 -0.160184 -0.987087 --0.000000 -0.707107 -0.707106 --0.000000 -0.701324 -0.712842 --0.000000 -0.986432 -0.164171 --0.000000 -0.986432 -0.164171 --0.000000 -0.987087 -0.160183 --0.000000 -0.707107 -0.707106 -0.000000 -0.686823 -0.726825 -0.000000 -0.686823 -0.726825 -0.000000 -0.906973 -0.421189 -0.000000 -0.906973 -0.421189 -0.000000 -0.906973 -0.421189 -0.000000 -0.686823 -0.726825 -0.000000 -0.906973 -0.421189 --0.144762 -0.898824 -0.413714 --0.107386 -0.671902 -0.732814 --0.107386 -0.671902 -0.732814 -0.000000 -0.686823 -0.726825 -0.000000 -0.906973 -0.421189 -0.160183 0.000000 -0.987087 -0.159277 0.000000 -0.987234 -0.699024 0.000000 -0.715099 -0.699024 0.000000 -0.715099 -0.707108 0.000000 -0.707105 -0.160183 0.000000 -0.987087 -0.707108 0.000000 -0.707105 -0.699024 0.000000 -0.715099 -0.986171 0.000000 -0.165731 -0.986171 0.000000 -0.165731 -0.987087 0.000000 -0.160182 -0.707108 0.000000 -0.707105 --0.987088 0.000000 -0.160181 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987088 0.000000 -0.160181 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987088 0.000000 -0.160181 --1.000000 0.000000 0.000000 --0.986171 0.000000 -0.165730 --0.986171 0.000000 -0.165730 --0.699024 0.000000 -0.715098 --0.707109 0.000000 -0.707105 --0.707109 0.000000 -0.707105 --0.987088 0.000000 -0.160181 --0.986171 0.000000 -0.165730 --0.699024 0.000000 -0.715098 --0.159277 0.000000 -0.987234 --0.160184 0.000000 -0.987087 --0.160184 0.000000 -0.987087 --0.707109 0.000000 -0.707105 --0.699024 0.000000 -0.715098 --0.159277 0.000000 -0.987234 -0.159277 0.000000 -0.987234 -0.160183 0.000000 -0.987087 -0.160183 0.000000 -0.987087 --0.160184 0.000000 -0.987087 --0.159277 0.000000 -0.987234 --0.987396 0.000000 0.158268 --0.974743 -0.158179 0.157659 --0.720099 -0.114166 0.684415 --0.720099 -0.114166 0.684415 --0.709858 0.000000 0.704345 --0.987396 0.000000 0.158268 --0.709858 0.000000 0.704345 --0.720099 -0.114166 0.684415 --0.173478 -0.024209 0.984540 --0.173478 -0.024209 0.984540 --0.162115 0.000000 0.986772 --0.709858 0.000000 0.704345 --0.162115 0.000000 0.986772 --0.162115 0.000000 0.986772 --0.709857 0.000000 0.704345 --0.709857 0.000000 0.704345 --0.709857 0.000000 0.704345 --0.162115 0.000000 0.986772 -0.000000 -0.707107 0.707106 -0.000001 -0.987087 0.160183 --0.000000 -0.987088 0.160181 --0.000000 -0.987088 0.160181 --0.000000 -0.707109 0.707105 -0.000000 -0.707107 0.707106 --0.000000 -0.160184 0.987087 --0.000000 -0.160183 0.987087 -0.000000 -0.707107 0.707106 -0.000000 -0.707107 0.707106 --0.000000 -0.707109 0.707105 --0.000000 -0.160184 0.987087 -0.000000 0.160183 0.987087 -0.000000 0.160183 0.987087 --0.000000 -0.160183 0.987087 --0.000000 -0.160183 0.987087 --0.000000 -0.160184 0.987087 -0.000000 0.160183 0.987087 -0.000000 0.707107 0.707106 -0.000000 0.707107 0.707106 -0.000000 0.160183 0.987087 -0.000000 0.160183 0.987087 -0.000000 0.160183 0.987087 -0.000000 0.707107 0.707106 -0.000001 0.987087 0.160183 -0.000001 0.987087 0.160183 -0.000000 0.707107 0.707106 -0.000000 0.707107 0.707106 -0.000000 0.707107 0.707106 -0.000001 0.987087 0.160183 -0.000000 -0.987396 0.158267 -0.000000 -0.709859 0.704344 -0.000000 -0.709859 0.704344 -0.000000 -0.709859 0.704344 -0.000000 -0.987396 0.158267 -0.000000 -0.987396 0.158267 -0.000000 -0.709859 0.704344 -0.000000 -0.162115 0.986772 -0.000000 -0.162115 0.986772 -0.000000 -0.162115 0.986772 -0.000000 -0.709859 0.704344 -0.000000 -0.709859 0.704344 -0.000000 -0.987396 0.158267 -0.000000 -0.709858 0.704344 --0.107470 -0.721820 0.683686 --0.107470 -0.721820 0.683686 --0.155746 -0.975487 0.155460 -0.000000 -0.987396 0.158267 --0.018551 -0.170483 0.985186 --0.107470 -0.721820 0.683686 -0.000000 -0.709858 0.704344 -0.000000 -0.709858 0.704344 -0.000000 -0.162115 0.986772 --0.018551 -0.170483 0.985186 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.707107 0.000000 0.707107 -0.707107 0.000000 0.707107 -0.707107 0.000000 0.707107 -0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.707108 0.000001 0.707105 --0.707108 0.000000 0.707106 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.707108 0.000001 0.707105 --0.987087 0.000000 0.160183 --0.707108 0.000000 0.707106 --0.707108 0.000001 0.707105 --0.707108 0.000001 0.707105 --0.987088 0.000001 0.160181 --0.987087 0.000000 0.160183 -0.707107 0.000000 0.707107 -0.707107 0.000000 0.707107 -0.987087 0.000000 0.160183 -0.987087 0.000000 0.160183 -0.987087 0.000000 0.160183 -0.707107 0.000000 0.707107 --0.911793 0.000000 -0.410650 --0.911793 0.000000 -0.410650 --0.999195 -0.000005 -0.040118 --0.999195 -0.000005 -0.040118 --0.999196 0.000000 -0.040096 --0.911793 0.000000 -0.410650 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000000 --0.000000 -0.987087 -0.160183 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000000 --0.000000 -0.987087 -0.160183 --0.000000 -1.000000 0.000000 --0.000000 -0.987087 -0.160183 --0.000000 -0.986432 -0.164171 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --0.000001 -0.998442 -0.055795 -0.000000 -0.999610 -0.027908 --0.000000 -0.999610 -0.027908 --0.000000 -0.999610 -0.027908 --0.000000 -0.998442 -0.055795 --0.000001 -0.998442 -0.055795 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.987087 0.000000 -0.160182 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.987087 0.000000 -0.160182 -1.000000 0.000000 0.000000 -0.987087 0.000000 -0.160182 -0.986171 0.000000 -0.165731 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 --0.000000 -1.000000 -0.000000 --1.000000 -0.000000 0.000001 --1.000000 0.000000 0.000000 --0.999799 0.000000 -0.020064 --0.999799 0.000000 -0.020064 --0.999799 -0.000000 -0.020062 --1.000000 -0.000000 0.000001 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 0.000000 -0.000001 -0.987087 0.160183 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 0.000000 -0.000001 -0.987087 0.160183 --0.000000 -1.000000 0.000000 --0.000000 -0.987088 0.160181 -0.000001 1.000000 -0.000000 -0.000001 1.000000 -0.000000 -0.000000 1.000000 0.000001 -0.000001 1.000000 -0.000000 -0.000000 1.000000 0.000001 -0.000000 1.000000 0.000000 -0.000001 1.000000 -0.000000 -0.000000 1.000000 0.000000 -0.000001 0.987087 0.160183 -0.000001 1.000000 -0.000000 -0.000001 0.987087 0.160183 -0.000001 0.987087 0.160183 --1.000000 0.000000 -0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 -0.000000 --0.162115 0.000000 0.986772 --0.162115 0.000000 0.986772 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.162115 0.000000 0.986772 --0.160182 -0.987087 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.987396 0.158267 -0.000000 -0.987396 0.158267 --0.155746 -0.975487 0.155460 --0.160182 -0.987087 0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --0.987088 0.000001 0.160181 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --0.987087 0.000000 0.160183 --0.987088 0.000001 0.160181 --1.000000 0.000000 -0.000000 --0.987087 0.000000 0.160183 --1.000000 0.000000 -0.000000 --1.000000 0.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.987087 0.000000 0.160183 -1.000000 0.000000 0.000000 -0.987087 0.000000 0.160183 -0.987087 0.000000 0.160183 -1.000000 0.000000 0.000000 -0.987087 0.000000 0.160183 -1.000000 0.000000 0.000000 --0.987396 0.000000 0.158268 --0.709857 0.000000 0.704345 --0.709857 0.000000 0.704345 --0.709857 0.000000 0.704345 --0.987396 0.000000 0.158268 --0.987396 0.000000 0.158268 -0.000000 0.000000 1.000000 --0.162115 0.000000 0.986772 --0.173478 -0.024209 0.984540 --0.018551 -0.170483 0.985186 -0.000000 -0.162115 0.986772 -0.000000 0.000000 1.000000 --0.173478 -0.024209 0.984540 --0.018551 -0.170483 0.985186 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.173478 -0.024209 0.984540 -0.000000 0.000000 1.000000 --0.173478 -0.024209 0.984540 --0.155928 -0.141040 0.977647 --0.018551 -0.170483 0.985186 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 -0.162115 0.986772 -0.000000 -0.162115 0.986772 -0.000000 -0.162115 0.986772 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.999195 0.000000 -0.040117 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999195 -0.000000 -0.040117 --0.999195 0.000000 -0.040117 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000001 --1.000000 -0.000000 0.000001 --0.999799 0.000000 -0.020062 --0.999195 0.000000 -0.040116 --0.985934 -0.159934 -0.048521 --0.985934 -0.159934 -0.048521 --0.985934 -0.159934 -0.048521 --0.999195 0.000000 -0.040117 --0.999195 0.000000 -0.040116 --0.974743 -0.158179 0.157659 --0.987396 0.000000 0.158268 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987087 -0.160182 0.000001 --0.974743 -0.158179 0.157659 --1.000000 0.000000 0.000001 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000001 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999195 0.000000 -0.040117 --0.999195 0.000000 -0.040117 --0.999195 0.000000 -0.040117 --0.999799 0.000000 -0.020062 --0.999195 -0.000000 -0.040117 --0.999799 0.000000 -0.020062 --0.999799 -0.000000 -0.020062 --0.999799 -0.000000 -0.020062 --0.999195 -0.000000 -0.040116 --0.999195 -0.000000 -0.040117 --0.999799 -0.000000 -0.020062 --0.999799 0.000000 -0.020062 --1.000000 -0.000000 0.000001 --1.000000 -0.000000 0.000001 --1.000000 -0.000000 0.000001 --0.999799 -0.000000 -0.020062 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 -0.000000 0.000001 --1.000000 0.000000 0.000000 --0.999195 -0.000000 -0.040116 --0.999196 0.000000 -0.040095 --0.999196 0.000000 -0.040096 --0.999196 0.000000 -0.040096 --0.999195 -0.000005 -0.040118 --0.999195 -0.000000 -0.040116 --1.000000 0.000000 0.000001 --0.987087 -0.160182 0.000000 --0.987087 -0.160182 0.000001 --0.987087 -0.160182 0.000001 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000001 --0.987087 -0.160182 0.000000 --0.707106 -0.707107 0.000000 --0.707107 -0.707107 0.000000 --0.707107 -0.707107 0.000000 --0.987087 -0.160182 0.000001 --0.987087 -0.160182 0.000000 --0.707106 -0.707107 0.000000 --0.160182 -0.987087 0.000000 --0.160182 -0.987087 0.000000 --0.160182 -0.987087 0.000000 --0.707107 -0.707107 0.000000 --0.707106 -0.707107 0.000000 --0.160182 -0.987087 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 --0.160182 -0.987087 0.000000 --0.160182 -0.987087 0.000000 --1.000000 0.000000 0.000001 --0.999799 0.000000 -0.020062 --0.986399 -0.162556 -0.024328 --0.986399 -0.162556 -0.024328 --0.987087 -0.160182 0.000000 --1.000000 0.000000 0.000001 --0.986399 -0.162556 -0.024328 --0.705633 -0.707781 -0.033588 --0.707106 -0.707107 0.000000 --0.707106 -0.707107 0.000000 --0.987087 -0.160182 0.000000 --0.986399 -0.162556 -0.024328 --0.705633 -0.707781 -0.033588 --0.161626 -0.986374 -0.030703 --0.160182 -0.987087 0.000000 --0.160182 -0.987087 0.000000 --0.707106 -0.707107 0.000000 --0.705633 -0.707781 -0.033588 -0.000000 -0.999610 -0.027908 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 --0.000000 -0.999610 -0.027908 -0.000000 -0.999610 -0.027908 --0.000001 -0.998442 -0.055795 -0.000001 -0.998442 -0.055795 -0.000000 -0.999610 -0.027908 -0.000000 -0.999610 -0.027908 -0.000000 -0.999610 -0.027908 --0.000001 -0.998442 -0.055795 -0.000000 -0.999610 -0.027908 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.999610 -0.027908 -0.000000 -0.999610 -0.027908 --0.161626 -0.986374 -0.030703 --0.000000 -0.999610 -0.027908 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 --0.160182 -0.987087 0.000000 --0.161626 -0.986374 -0.030703 --0.159831 -0.985228 -0.061474 --0.159831 -0.985228 -0.061474 --0.000000 -0.998442 -0.055794 --0.000000 -0.998442 -0.055794 --0.000000 -0.998442 -0.055795 --0.159831 -0.985228 -0.061474 --0.000000 -0.999610 -0.027908 --0.161626 -0.986374 -0.030703 --0.159831 -0.985228 -0.061474 --0.159831 -0.985228 -0.061474 --0.000000 -0.998442 -0.055795 --0.000000 -0.999610 -0.027908 --0.161626 -0.986374 -0.030703 --0.705633 -0.707781 -0.033588 --0.705588 -0.705376 -0.067746 --0.705588 -0.705376 -0.067746 --0.159831 -0.985228 -0.061474 --0.161626 -0.986374 -0.030703 --0.705588 -0.705376 -0.067746 --0.705633 -0.707781 -0.033588 --0.986399 -0.162556 -0.024328 --0.986399 -0.162556 -0.024328 --0.985934 -0.159934 -0.048521 --0.705588 -0.705376 -0.067746 --0.999195 0.000000 -0.040117 --0.985934 -0.159934 -0.048521 --0.986399 -0.162556 -0.024328 --0.986399 -0.162556 -0.024328 --0.999799 0.000000 -0.020062 --0.999195 0.000000 -0.040117 --0.999195 0.000000 -0.040116 --0.911793 0.000000 -0.410650 --0.902713 -0.144766 -0.405157 --0.902713 -0.144766 -0.405157 --0.985934 -0.159934 -0.048521 --0.999195 0.000000 -0.040116 --0.985934 -0.159934 -0.048521 --0.902713 -0.144766 -0.405157 --0.645117 -0.643053 -0.412683 --0.645117 -0.643053 -0.412683 --0.705588 -0.705377 -0.067746 --0.985934 -0.159934 -0.048521 --0.645117 -0.643053 -0.412683 --0.144762 -0.898824 -0.413714 --0.159831 -0.985228 -0.061474 --0.159831 -0.985228 -0.061474 --0.705588 -0.705377 -0.067746 --0.645117 -0.643053 -0.412683 --0.144762 -0.898824 -0.413714 -0.000000 -0.906973 -0.421189 --0.000000 -0.998442 -0.055794 --0.000000 -0.998442 -0.055794 --0.159831 -0.985228 -0.061474 --0.144762 -0.898824 -0.413714 --0.000000 -0.998441 -0.055810 -0.000000 -0.999611 -0.027905 --0.000001 -0.999610 -0.027908 --0.000001 -0.999610 -0.027908 --0.000005 -0.998442 -0.055795 --0.000000 -0.998441 -0.055810 -0.000000 -0.987396 0.158267 -0.000000 -0.987396 0.158267 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.987396 0.158267 -0.000000 -1.000000 0.000000 -0.000000 -0.999610 -0.027908 --0.000001 -0.999610 -0.027908 --0.000001 -0.999610 -0.027908 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 --0.000001 -0.999610 -0.027908 -0.000000 -0.999610 -0.027908 -0.000001 -0.998442 -0.055795 -0.000001 -0.998442 -0.055795 --0.000005 -0.998442 -0.055795 --0.000001 -0.999610 -0.027908 --0.000002 -0.998442 -0.055798 --0.000000 -0.998441 -0.055815 --0.000000 -0.998441 -0.055810 --0.000000 -0.998441 -0.055810 --0.000005 -0.998442 -0.055795 --0.000002 -0.998442 -0.055798 --0.000002 -0.998442 -0.055798 -0.000000 -0.906973 -0.421189 -0.000000 -0.906973 -0.421189 -0.000000 -0.906973 -0.421189 --0.000000 -0.998441 -0.055815 --0.000002 -0.998442 -0.055798 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 --0.000001 -0.999610 -0.027908 -0.000000 -0.999611 -0.027905 -0.000000 -0.999611 -0.027905 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 --0.987396 0.000000 0.158268 --0.987396 0.000000 0.158268 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000000 --0.987396 0.000000 0.158268 --0.999195 -0.000000 -0.040116 --0.999799 -0.000000 -0.020062 --0.999799 0.000000 -0.020064 --0.999799 0.000000 -0.020064 --0.999196 0.000000 -0.040095 --0.999195 -0.000000 -0.040116 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000001 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000001 --1.000000 0.000000 -0.000001 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000001 --1.000000 0.000000 -0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --1.000000 0.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000001 --0.000000 -1.000000 0.000001 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000001 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000003 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000001 --0.000000 -1.000000 0.000021 -0.000000 -1.000000 0.000003 -0.000000 -1.000000 0.000003 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000001 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.293668 -0.950362 -0.102818 --0.378489 -0.922436 0.076533 -0.466777 -0.877351 -0.111237 -0.466777 -0.877351 -0.111237 -0.437377 -0.898427 0.039117 --0.293668 -0.950362 -0.102818 --0.000000 -1.000000 0.000002 -0.000000 -0.928568 -0.371161 --0.053947 -0.933079 -0.355602 --0.053947 -0.933079 -0.355602 -0.000000 -1.000000 0.000002 --0.000000 -1.000000 0.000002 -0.083860 -0.883048 -0.461729 -0.334821 -0.862576 -0.379284 --0.219047 -0.944662 0.244197 --0.219047 -0.944662 0.244197 --0.058021 -0.917041 0.394549 -0.083860 -0.883048 -0.461729 -0.278630 -0.944534 0.173843 -0.204871 -0.931518 0.300504 --0.126855 -0.942566 -0.308993 --0.126855 -0.942566 -0.308993 --0.199706 -0.956891 -0.210898 -0.278630 -0.944534 0.173843 -0.437377 -0.898427 0.039117 -0.278630 -0.944534 0.173843 --0.199706 -0.956891 -0.210898 --0.199706 -0.956891 -0.210898 --0.293668 -0.950362 -0.102818 -0.437377 -0.898427 0.039117 -0.000000 -0.902777 -0.430109 -0.083860 -0.883048 -0.461729 --0.058021 -0.917041 0.394549 --0.058021 -0.917041 0.394549 -0.000000 -0.903393 0.428813 -0.000000 -0.902777 -0.430109 --0.219047 -0.944662 0.244197 -0.334821 -0.862576 -0.379284 -0.466777 -0.877351 -0.111237 -0.466777 -0.877351 -0.111237 --0.378489 -0.922436 0.076533 --0.219047 -0.944662 0.244197 -0.204871 -0.931518 0.300504 -0.000000 -1.000000 0.000002 --0.053947 -0.933079 -0.355602 --0.053947 -0.933079 -0.355602 --0.126855 -0.942566 -0.308993 -0.204871 -0.931518 0.300504 --0.984855 -0.000001 0.173381 --0.924386 -0.345298 0.162109 --0.906193 -0.386266 -0.172083 --0.906193 -0.386266 -0.172083 --0.973923 0.000000 -0.226877 --0.984855 -0.000001 0.173381 -0.965948 0.000000 0.258737 -0.876796 -0.404449 0.260095 -0.922754 -0.317517 -0.218422 -0.922754 -0.317517 -0.218422 -0.972507 0.000000 -0.232875 -0.965948 0.000000 0.258737 -0.000000 0.000000 1.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.165253 0.000000 -0.986251 --0.145080 -0.399992 -0.904963 -0.000000 -0.389580 -0.920992 -0.000000 -0.389580 -0.920992 -0.000000 0.000000 -1.000000 --0.165253 0.000000 -0.986251 -0.661497 0.000000 -0.749948 -0.628452 -0.312262 -0.712418 -0.161326 -0.320071 -0.933557 -0.161326 -0.320071 -0.933557 -0.174458 0.000000 -0.984665 -0.661497 0.000000 -0.749948 --0.139943 0.000000 0.990160 --0.134000 -0.341445 0.930301 --0.629331 -0.383170 0.676108 --0.629331 -0.383170 0.676108 --0.682762 -0.000000 0.730641 --0.139943 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 --0.000001 -0.480135 -0.877194 -0.472043 -0.840449 -0.266122 -0.472043 -0.840449 -0.266122 -0.865983 0.000000 -0.500074 -0.000000 0.000000 -1.000000 --0.973923 0.000000 -0.226877 --0.906193 -0.386266 -0.172083 --0.686198 -0.460064 -0.563448 --0.686198 -0.460064 -0.563448 --0.766123 0.000000 -0.642694 --0.973923 0.000000 -0.226877 -0.865983 0.000000 -0.500074 -0.472043 -0.840449 -0.266122 -0.876796 -0.404449 0.260095 -0.876796 -0.404449 0.260095 -0.965948 0.000000 0.258737 -0.865983 0.000000 -0.500074 -0.000000 0.000000 1.000000 -0.000000 -0.335574 0.942014 --0.134000 -0.341445 0.930301 --0.134000 -0.341445 0.930301 --0.139943 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.174458 0.000000 -0.984665 -0.161326 -0.320071 -0.933557 --0.000000 -0.335181 -0.942154 --0.000000 -0.335181 -0.942154 -0.000000 0.000000 -1.000000 -0.174458 0.000000 -0.984665 -0.972507 0.000000 -0.232875 -0.922754 -0.317517 -0.218422 -0.628452 -0.312262 -0.712418 -0.628452 -0.312262 -0.712418 -0.661497 0.000000 -0.749948 -0.972507 0.000000 -0.232875 --0.682762 -0.000000 0.730641 --0.629331 -0.383170 0.676108 --0.924386 -0.345298 0.162109 --0.924386 -0.345298 0.162109 --0.984855 -0.000001 0.173381 --0.682762 -0.000000 0.730641 --0.446771 0.000000 -0.894648 --0.391985 -0.437360 -0.809360 --0.145080 -0.399992 -0.904963 --0.145080 -0.399992 -0.904963 --0.165253 0.000000 -0.986251 --0.446771 0.000000 -0.894648 --0.766123 0.000000 -0.642694 --0.686198 -0.460064 -0.563448 --0.391985 -0.437360 -0.809360 --0.391985 -0.437360 -0.809360 --0.446771 0.000000 -0.894648 --0.766123 0.000000 -0.642694 -0.437377 -0.898427 0.039117 -0.466777 -0.877351 -0.111237 -0.922754 -0.317517 -0.218422 -0.922754 -0.317517 -0.218422 -0.876796 -0.404449 0.260095 -0.437377 -0.898427 0.039117 --0.378489 -0.922436 0.076533 --0.293668 -0.950362 -0.102818 --0.906193 -0.386266 -0.172083 --0.906193 -0.386266 -0.172083 --0.924386 -0.345298 0.162109 --0.378489 -0.922436 0.076533 -0.000000 -0.960502 0.278273 --0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.016761 -0.961573 0.274037 -0.000000 -0.960502 0.278273 --0.145080 -0.399992 -0.904963 --0.053947 -0.933079 -0.355602 -0.000000 -0.928568 -0.371161 -0.000000 -0.928568 -0.371161 -0.000000 -0.389580 -0.920992 --0.145080 -0.399992 -0.904963 --0.058021 -0.917041 0.394549 --0.219047 -0.944662 0.244197 --0.629331 -0.383170 0.676108 --0.629331 -0.383170 0.676108 --0.134000 -0.341445 0.930301 --0.058021 -0.917041 0.394549 -0.334821 -0.862576 -0.379284 -0.083860 -0.883048 -0.461729 -0.161326 -0.320071 -0.933557 -0.161326 -0.320071 -0.933557 -0.628452 -0.312262 -0.712418 -0.334821 -0.862576 -0.379284 --0.199706 -0.956891 -0.210898 --0.126855 -0.942566 -0.308993 --0.391985 -0.437360 -0.809360 --0.391985 -0.437360 -0.809360 --0.686198 -0.460064 -0.563448 --0.199706 -0.956891 -0.210898 --0.293668 -0.950362 -0.102818 --0.199706 -0.956891 -0.210898 --0.686198 -0.460064 -0.563448 --0.686198 -0.460064 -0.563448 --0.906193 -0.386266 -0.172083 --0.293668 -0.950362 -0.102818 -0.278630 -0.944534 0.173843 -0.437377 -0.898427 0.039117 -0.876796 -0.404449 0.260095 -0.876796 -0.404449 0.260095 -0.472043 -0.840449 -0.266122 -0.278630 -0.944534 0.173843 -0.000000 -0.903393 0.428813 --0.058021 -0.917041 0.394549 --0.134000 -0.341445 0.930301 --0.134000 -0.341445 0.930301 -0.000000 -0.335574 0.942014 -0.000000 -0.903393 0.428813 -0.161326 -0.320071 -0.933557 -0.083860 -0.883048 -0.461729 -0.000000 -0.902777 -0.430109 -0.000000 -0.902777 -0.430109 --0.000000 -0.335181 -0.942154 -0.161326 -0.320071 -0.933557 --0.629331 -0.383170 0.676108 --0.219047 -0.944662 0.244197 --0.378489 -0.922436 0.076533 --0.378489 -0.922436 0.076533 --0.924386 -0.345298 0.162109 --0.629331 -0.383170 0.676108 -0.922754 -0.317517 -0.218422 -0.466777 -0.877351 -0.111237 -0.334821 -0.862576 -0.379284 -0.334821 -0.862576 -0.379284 -0.628452 -0.312262 -0.712418 -0.922754 -0.317517 -0.218422 --0.126855 -0.942566 -0.308993 --0.053947 -0.933079 -0.355602 --0.145080 -0.399992 -0.904963 --0.145080 -0.399992 -0.904963 --0.391985 -0.437360 -0.809360 --0.126855 -0.942566 -0.308993 -0.204871 -0.931518 0.300504 -0.472043 -0.840449 -0.266122 -0.016761 -0.961573 0.274037 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.960502 0.278273 -0.016761 -0.961573 0.274037 -0.016761 -0.961573 0.274037 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.016761 -0.961573 0.274037 -0.000000 -0.999997 -0.002593 -0.000000 -0.999997 -0.002593 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.016761 -0.961573 0.274037 -0.000000 -1.000000 0.000002 -0.204871 -0.931518 0.300504 -0.204871 -0.931518 0.300504 -0.278630 -0.944534 0.173843 -0.472043 -0.840449 -0.266122 --0.000001 -0.480135 -0.877194 -0.000000 -0.999997 -0.002593 -0.016761 -0.961573 0.274037 -0.016761 -0.961573 0.274037 -0.472043 -0.840449 -0.266122 --0.000001 -0.480135 -0.877194 -0.293668 -0.950362 -0.102818 --0.437377 -0.898427 0.039117 --0.466777 -0.877352 -0.111236 --0.466777 -0.877352 -0.111236 -0.378489 -0.922436 0.076533 -0.293668 -0.950362 -0.102818 --0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.053947 -0.933079 -0.355603 -0.053947 -0.933079 -0.355603 -0.000000 -0.928568 -0.371161 --0.000000 -1.000000 0.000002 --0.083860 -0.883048 -0.461729 -0.058021 -0.917041 0.394549 -0.219047 -0.944662 0.244196 -0.219047 -0.944662 0.244196 --0.334821 -0.862576 -0.379285 --0.083860 -0.883048 -0.461729 --0.278630 -0.944534 0.173843 -0.199706 -0.956891 -0.210898 -0.126855 -0.942566 -0.308993 -0.126855 -0.942566 -0.308993 --0.204871 -0.931518 0.300504 --0.278630 -0.944534 0.173843 --0.437377 -0.898427 0.039117 -0.293668 -0.950362 -0.102818 -0.199706 -0.956891 -0.210898 -0.199706 -0.956891 -0.210898 --0.278630 -0.944534 0.173843 --0.437377 -0.898427 0.039117 -0.000000 -0.902777 -0.430109 -0.000000 -0.903393 0.428813 -0.058021 -0.917041 0.394549 -0.058021 -0.917041 0.394549 --0.083860 -0.883048 -0.461729 -0.000000 -0.902777 -0.430109 -0.219047 -0.944662 0.244196 -0.378489 -0.922436 0.076533 --0.466777 -0.877352 -0.111236 --0.466777 -0.877352 -0.111236 --0.334821 -0.862576 -0.379285 -0.219047 -0.944662 0.244196 --0.204871 -0.931518 0.300504 -0.126855 -0.942566 -0.308993 -0.053947 -0.933079 -0.355603 -0.053947 -0.933079 -0.355603 -0.000000 -1.000000 0.000002 --0.204871 -0.931518 0.300504 -0.984855 -0.000001 0.173382 -0.973923 0.000000 -0.226877 -0.906193 -0.386266 -0.172082 -0.906193 -0.386266 -0.172082 -0.924386 -0.345297 0.162111 -0.984855 -0.000001 0.173382 --0.965948 0.000000 0.258737 --0.972507 0.000000 -0.232875 --0.922754 -0.317518 -0.218422 --0.922754 -0.317518 -0.218422 --0.876796 -0.404449 0.260094 --0.965948 0.000000 0.258737 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 0.000000 1.000000 -0.165253 0.000000 -0.986251 -0.000000 0.000000 -1.000000 -0.000000 -0.389580 -0.920992 -0.000000 -0.389580 -0.920992 -0.145080 -0.399992 -0.904963 -0.165253 0.000000 -0.986251 --0.661497 0.000000 -0.749948 --0.174458 0.000000 -0.984665 --0.161326 -0.320071 -0.933557 --0.161326 -0.320071 -0.933557 --0.628452 -0.312262 -0.712418 --0.661497 0.000000 -0.749948 -0.139943 0.000000 0.990160 -0.682761 -0.000001 0.730642 -0.629330 -0.383170 0.676110 -0.629330 -0.383170 0.676110 -0.134000 -0.341445 0.930301 -0.139943 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 0.000000 1.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 --0.865983 0.000000 -0.500074 --0.472044 -0.840449 -0.266122 --0.472044 -0.840449 -0.266122 -0.000001 -0.480135 -0.877194 -0.000000 0.000000 -1.000000 -0.973923 0.000000 -0.226877 -0.766123 0.000000 -0.642694 -0.686198 -0.460064 -0.563448 -0.686198 -0.460064 -0.563448 -0.906193 -0.386266 -0.172082 -0.973923 0.000000 -0.226877 --0.865983 0.000000 -0.500074 --0.965948 0.000000 0.258737 --0.876796 -0.404449 0.260094 --0.876796 -0.404449 0.260094 --0.472044 -0.840449 -0.266122 --0.865983 0.000000 -0.500074 -0.000000 0.000000 1.000000 -0.139943 0.000000 0.990160 -0.134000 -0.341445 0.930301 -0.134000 -0.341445 0.930301 -0.000000 -0.335574 0.942014 -0.000000 0.000000 1.000000 --0.174458 0.000000 -0.984665 -0.000000 0.000000 -1.000000 --0.000000 -0.335181 -0.942154 --0.000000 -0.335181 -0.942154 --0.161326 -0.320071 -0.933557 --0.174458 0.000000 -0.984665 --0.972507 0.000000 -0.232875 --0.661497 0.000000 -0.749948 --0.628452 -0.312262 -0.712418 --0.628452 -0.312262 -0.712418 --0.922754 -0.317518 -0.218422 --0.972507 0.000000 -0.232875 -0.682761 -0.000001 0.730642 -0.984855 -0.000001 0.173382 -0.924386 -0.345297 0.162111 -0.924386 -0.345297 0.162111 -0.629330 -0.383170 0.676110 -0.682761 -0.000001 0.730642 -0.446771 0.000000 -0.894648 -0.165253 0.000000 -0.986251 -0.145080 -0.399992 -0.904963 -0.145080 -0.399992 -0.904963 -0.391985 -0.437360 -0.809360 -0.446771 0.000000 -0.894648 -0.766123 0.000000 -0.642694 -0.446771 0.000000 -0.894648 -0.391985 -0.437360 -0.809360 -0.391985 -0.437360 -0.809360 -0.686198 -0.460064 -0.563448 -0.766123 0.000000 -0.642694 --0.437377 -0.898427 0.039117 --0.876796 -0.404449 0.260094 --0.922754 -0.317518 -0.218422 --0.922754 -0.317518 -0.218422 --0.466777 -0.877352 -0.111236 --0.437377 -0.898427 0.039117 -0.378489 -0.922436 0.076533 -0.924386 -0.345297 0.162111 -0.906193 -0.386266 -0.172082 -0.906193 -0.386266 -0.172082 -0.293668 -0.950362 -0.102818 -0.378489 -0.922436 0.076533 -0.000000 -0.960502 0.278273 --0.016761 -0.961573 0.274037 -0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 --0.000000 -1.000000 0.000002 -0.000000 -0.960502 0.278273 -0.145080 -0.399992 -0.904963 -0.000000 -0.389580 -0.920992 -0.000000 -0.928568 -0.371161 -0.000000 -0.928568 -0.371161 -0.053947 -0.933079 -0.355603 -0.145080 -0.399992 -0.904963 -0.058021 -0.917041 0.394549 -0.134000 -0.341445 0.930301 -0.629330 -0.383170 0.676110 -0.629330 -0.383170 0.676110 -0.219047 -0.944662 0.244196 -0.058021 -0.917041 0.394549 --0.334821 -0.862576 -0.379285 --0.628452 -0.312262 -0.712418 --0.161326 -0.320071 -0.933557 --0.161326 -0.320071 -0.933557 --0.083860 -0.883048 -0.461729 --0.334821 -0.862576 -0.379285 -0.199706 -0.956891 -0.210898 -0.686198 -0.460064 -0.563448 -0.391985 -0.437360 -0.809360 -0.391985 -0.437360 -0.809360 -0.126855 -0.942566 -0.308993 -0.199706 -0.956891 -0.210898 -0.293668 -0.950362 -0.102818 -0.906193 -0.386266 -0.172082 -0.686198 -0.460064 -0.563448 -0.686198 -0.460064 -0.563448 -0.199706 -0.956891 -0.210898 -0.293668 -0.950362 -0.102818 --0.278630 -0.944534 0.173843 --0.472044 -0.840449 -0.266122 --0.876796 -0.404449 0.260094 --0.876796 -0.404449 0.260094 --0.437377 -0.898427 0.039117 --0.278630 -0.944534 0.173843 -0.000000 -0.903393 0.428813 -0.000000 -0.335574 0.942014 -0.134000 -0.341445 0.930301 -0.134000 -0.341445 0.930301 -0.058021 -0.917041 0.394549 -0.000000 -0.903393 0.428813 --0.161326 -0.320071 -0.933557 --0.000000 -0.335181 -0.942154 -0.000000 -0.902777 -0.430109 -0.000000 -0.902777 -0.430109 --0.083860 -0.883048 -0.461729 --0.161326 -0.320071 -0.933557 -0.629330 -0.383170 0.676110 -0.924386 -0.345297 0.162111 -0.378489 -0.922436 0.076533 -0.378489 -0.922436 0.076533 -0.219047 -0.944662 0.244196 -0.629330 -0.383170 0.676110 --0.922754 -0.317518 -0.218422 --0.628452 -0.312262 -0.712418 --0.334821 -0.862576 -0.379285 --0.334821 -0.862576 -0.379285 --0.466777 -0.877352 -0.111236 --0.922754 -0.317518 -0.218422 -0.126855 -0.942566 -0.308993 -0.391985 -0.437360 -0.809360 -0.145080 -0.399992 -0.904963 -0.145080 -0.399992 -0.904963 -0.053947 -0.933079 -0.355603 -0.126855 -0.942566 -0.308993 --0.204871 -0.931518 0.300504 --0.016761 -0.961573 0.274037 --0.472044 -0.840449 -0.266122 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 --0.016761 -0.961573 0.274037 --0.016761 -0.961573 0.274037 -0.000000 -0.960502 0.278273 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.999997 -0.002593 -0.000000 -0.999997 -0.002593 --0.016761 -0.961573 0.274037 -0.000000 -0.482408 0.875946 --0.016761 -0.961573 0.274037 --0.204871 -0.931518 0.300504 -0.000000 -1.000000 0.000002 --0.204871 -0.931518 0.300504 --0.472044 -0.840449 -0.266122 --0.278630 -0.944534 0.173843 -0.000001 -0.480135 -0.877194 --0.472044 -0.840449 -0.266122 --0.016761 -0.961573 0.274037 --0.016761 -0.961573 0.274037 -0.000000 -0.999997 -0.002593 -0.000001 -0.480135 -0.877194 -0.159831 -0.985228 -0.061474 -0.159831 -0.985228 -0.061474 -0.705588 -0.705377 -0.067746 -0.705588 -0.705377 -0.067746 -0.705588 -0.705376 -0.067746 -0.159831 -0.985228 -0.061474 -0.987087 -0.160182 0.000001 -0.974743 -0.158179 0.157659 -0.700074 -0.696893 0.155682 -0.700074 -0.696893 0.155682 -0.707107 -0.707107 0.000000 -0.987087 -0.160182 0.000001 -0.705588 -0.705377 -0.067746 -0.985935 -0.159933 -0.048523 -0.985934 -0.159933 -0.048522 -0.985934 -0.159933 -0.048522 -0.705588 -0.705376 -0.067746 -0.705588 -0.705377 -0.067746 -0.707107 -0.707107 0.000000 -0.700074 -0.696893 0.155682 -0.155746 -0.975487 0.155460 -0.155746 -0.975487 0.155460 -0.160182 -0.987087 0.000000 -0.707107 -0.707107 0.000000 -0.155927 -0.141040 0.977647 -0.018551 -0.170483 0.985186 -0.107470 -0.721820 0.683686 -0.107470 -0.721820 0.683686 -0.541661 -0.532698 0.650258 -0.155927 -0.141040 0.977647 -0.173478 -0.024209 0.984540 -0.155927 -0.141040 0.977647 -0.541661 -0.532698 0.650258 -0.541661 -0.532698 0.650258 -0.720099 -0.114166 0.684415 -0.173478 -0.024209 0.984540 -0.541661 -0.532698 0.650258 -0.107470 -0.721820 0.683686 -0.155746 -0.975487 0.155460 -0.155746 -0.975487 0.155460 -0.700074 -0.696893 0.155682 -0.541661 -0.532698 0.650258 -0.720099 -0.114166 0.684415 -0.541661 -0.532698 0.650258 -0.700074 -0.696893 0.155682 -0.700074 -0.696893 0.155682 -0.974743 -0.158179 0.157659 -0.720099 -0.114166 0.684415 -0.902713 -0.144766 -0.405157 -0.645117 -0.643053 -0.412683 -0.456612 -0.453865 -0.765188 -0.456612 -0.453865 -0.765188 -0.676471 -0.107126 -0.728637 -0.902713 -0.144766 -0.405157 -0.456612 -0.453865 -0.765188 -0.645117 -0.643053 -0.412683 -0.144762 -0.898824 -0.413714 -0.144762 -0.898824 -0.413714 -0.107386 -0.671902 -0.732814 -0.456612 -0.453865 -0.765188 -0.676471 -0.107126 -0.728637 -0.692241 0.000000 -0.721666 -0.911793 0.000000 -0.410650 -0.911793 0.000000 -0.410650 -0.902713 -0.144766 -0.405157 -0.676471 -0.107126 -0.728637 -0.911793 0.000000 -0.410650 -0.911793 0.000000 -0.410650 -0.692241 0.000000 -0.721666 -0.692241 0.000000 -0.721666 -0.692242 0.000000 -0.721666 -0.911793 0.000000 -0.410650 -0.000000 0.987087 -0.160182 -0.000000 0.986432 -0.164170 -0.000000 1.000000 0.000000 -0.000000 0.987087 -0.160182 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.987087 -0.160182 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.986432 -0.164170 -0.000000 0.987087 -0.160182 -0.000000 0.707108 -0.707105 -0.000000 0.707108 -0.707105 -0.000000 0.701325 -0.712842 -0.000000 0.986432 -0.164170 -0.000000 0.701325 -0.712842 -0.000000 0.707108 -0.707105 -0.000000 0.160184 -0.987087 -0.000000 0.160184 -0.987087 -0.000000 0.159534 -0.987193 -0.000000 0.701325 -0.712842 -0.000000 0.159534 -0.987193 -0.000000 0.160184 -0.987087 -0.000000 -0.160184 -0.987087 -0.000000 -0.160184 -0.987087 -0.000000 -0.159534 -0.987192 -0.000000 0.159534 -0.987193 -0.000000 -0.160184 -0.987087 -0.000000 -0.707107 -0.707106 -0.000000 -0.701324 -0.712843 -0.000000 -0.701324 -0.712843 -0.000000 -0.159534 -0.987192 -0.000000 -0.160184 -0.987087 -0.000000 -0.707107 -0.707106 -0.000000 -0.987087 -0.160183 -0.000000 -0.986432 -0.164171 -0.000000 -0.986432 -0.164171 -0.000000 -0.701324 -0.712843 -0.000000 -0.707107 -0.707106 -0.000000 -0.686823 -0.726825 -0.000000 -0.906973 -0.421189 -0.000000 -0.906973 -0.421189 -0.000000 -0.906973 -0.421189 -0.000000 -0.686823 -0.726825 -0.000000 -0.686823 -0.726825 -0.000000 -0.906973 -0.421189 -0.000000 -0.686823 -0.726825 -0.107386 -0.671902 -0.732814 -0.107386 -0.671902 -0.732814 -0.144762 -0.898824 -0.413714 -0.000000 -0.906973 -0.421189 --0.160183 0.000000 -0.987087 --0.707108 0.000000 -0.707105 --0.699024 0.000000 -0.715098 --0.699024 0.000000 -0.715098 --0.159277 0.000000 -0.987234 --0.160183 0.000000 -0.987087 --0.707108 0.000000 -0.707105 --0.987088 0.000000 -0.160181 --0.986171 0.000000 -0.165730 --0.986171 0.000000 -0.165730 --0.699024 0.000000 -0.715098 --0.707108 0.000000 -0.707105 -0.987088 0.000000 -0.160181 -0.986171 0.000000 -0.165731 -1.000000 0.000000 0.000000 -0.987088 0.000000 -0.160181 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.987088 0.000000 -0.160181 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.986171 0.000000 -0.165731 -0.987088 0.000000 -0.160181 -0.707109 0.000000 -0.707105 -0.707109 0.000000 -0.707105 -0.699024 0.000000 -0.715098 -0.986171 0.000000 -0.165731 -0.699024 0.000000 -0.715098 -0.707109 0.000000 -0.707105 -0.160184 0.000000 -0.987087 -0.160184 0.000000 -0.987087 -0.159277 0.000000 -0.987234 -0.699024 0.000000 -0.715098 -0.159277 0.000000 -0.987234 -0.160184 0.000000 -0.987087 --0.160183 0.000000 -0.987087 --0.160183 0.000000 -0.987087 --0.159277 0.000000 -0.987234 -0.159277 0.000000 -0.987234 -0.987396 0.000000 0.158268 -0.709858 0.000000 0.704345 -0.720099 -0.114166 0.684415 -0.720099 -0.114166 0.684415 -0.974743 -0.158179 0.157659 -0.987396 0.000000 0.158268 -0.709858 0.000000 0.704345 -0.162115 0.000000 0.986772 -0.173478 -0.024209 0.984540 -0.173478 -0.024209 0.984540 -0.720099 -0.114166 0.684415 -0.709858 0.000000 0.704345 -0.162115 0.000000 0.986772 -0.709858 0.000000 0.704345 -0.709857 0.000000 0.704345 -0.709857 0.000000 0.704345 -0.162115 0.000000 0.986772 -0.162115 0.000000 0.986772 --0.000000 -0.707107 0.707106 -0.000000 -0.707109 0.707105 -0.000000 -0.987088 0.160181 -0.000000 -0.987088 0.160181 --0.000001 -0.987087 0.160183 --0.000000 -0.707107 0.707106 -0.000000 -0.160184 0.987087 -0.000000 -0.707109 0.707105 --0.000000 -0.707107 0.707106 --0.000000 -0.707107 0.707106 -0.000000 -0.160183 0.987087 -0.000000 -0.160184 0.987087 --0.000000 0.160183 0.987087 -0.000000 -0.160184 0.987087 -0.000000 -0.160183 0.987087 -0.000000 -0.160183 0.987087 --0.000000 0.160183 0.987087 --0.000000 0.160183 0.987087 --0.000000 0.707107 0.707106 --0.000000 0.160183 0.987087 --0.000000 0.160183 0.987087 --0.000000 0.160183 0.987087 --0.000000 0.707107 0.707106 --0.000000 0.707107 0.707106 --0.000001 0.987087 0.160183 --0.000000 0.707107 0.707106 --0.000000 0.707107 0.707106 --0.000000 0.707107 0.707106 --0.000001 0.987087 0.160183 --0.000001 0.987087 0.160183 -0.000000 -0.987396 0.158267 -0.000000 -0.987396 0.158267 -0.000000 -0.709859 0.704344 -0.000000 -0.709859 0.704344 -0.000000 -0.709859 0.704344 -0.000000 -0.987396 0.158267 -0.000000 -0.709859 0.704344 -0.000000 -0.709859 0.704344 -0.000000 -0.162115 0.986772 -0.000000 -0.162115 0.986772 -0.000000 -0.162115 0.986772 -0.000000 -0.709859 0.704344 -0.000000 -0.987396 0.158267 -0.155746 -0.975487 0.155460 -0.107470 -0.721820 0.683686 -0.107470 -0.721820 0.683686 -0.000000 -0.709858 0.704344 -0.000000 -0.987396 0.158267 -0.018551 -0.170483 0.985186 -0.000000 -0.162115 0.986772 -0.000000 -0.709858 0.704344 -0.000000 -0.709858 0.704344 -0.107470 -0.721820 0.683686 -0.018551 -0.170483 0.985186 --0.160184 0.000000 0.987087 --0.707107 0.000000 0.707106 --0.707107 0.000000 0.707106 --0.707107 0.000000 0.707106 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.707108 0.000001 0.707105 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.707108 0.000000 0.707106 -0.707108 0.000001 0.707105 -0.987087 0.000000 0.160183 -0.987088 0.000001 0.160180 -0.707108 0.000001 0.707105 -0.707108 0.000001 0.707105 -0.707108 0.000000 0.707106 -0.987087 0.000000 0.160183 --0.707107 0.000000 0.707106 --0.987087 0.000000 0.160183 --0.987087 0.000000 0.160183 --0.987087 0.000000 0.160183 --0.707107 0.000000 0.707106 --0.707107 0.000000 0.707106 -0.911793 0.000000 -0.410650 -0.999196 -0.000000 -0.040096 -0.999195 -0.000005 -0.040120 -0.999195 -0.000005 -0.040120 -0.911793 0.000000 -0.410650 -0.911793 0.000000 -0.410650 -0.000000 -1.000000 0.000000 -0.000000 -0.986432 -0.164171 -0.000000 -0.987087 -0.160183 -0.000000 -0.987087 -0.160183 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.987087 -0.160183 -0.000000 -1.000000 0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.000001 -0.998442 -0.055795 -0.000000 -0.998442 -0.055795 -0.000000 -0.999610 -0.027908 -0.000000 -0.999610 -0.027908 -0.000000 -0.999611 -0.027908 -0.000001 -0.998442 -0.055795 --1.000000 0.000000 0.000000 --0.986171 0.000000 -0.165730 --0.987088 0.000000 -0.160181 --0.987088 0.000000 -0.160181 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987088 0.000000 -0.160181 --1.000000 0.000000 0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -1.000000 -0.000000 0.000001 -0.999799 -0.000000 -0.020062 -0.999799 0.000000 -0.020063 -0.999799 0.000000 -0.020063 -1.000000 0.000000 0.000000 -1.000000 -0.000000 0.000001 --0.000001 -0.987087 0.160183 -0.000000 -0.987088 0.160181 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 --0.000001 -0.987087 0.160183 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 -0.000000 --0.000001 1.000000 -0.000000 --0.000001 0.987087 0.160183 --0.000001 0.987087 0.160183 --0.000001 1.000000 -0.000000 --0.000001 0.987087 0.160183 --0.000000 1.000000 0.000000 --0.000001 1.000000 -0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000001 --0.000001 1.000000 -0.000000 --0.000000 1.000000 0.000001 --0.000001 1.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 -0.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.160182 -0.987087 0.000000 -0.155746 -0.975487 0.155460 -0.000000 -0.987396 0.158267 -0.000000 -0.987396 0.158267 -0.000000 -1.000000 0.000000 -0.160182 -0.987087 0.000000 -0.987087 0.000000 0.160183 -1.000000 0.000000 0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000001 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.987088 0.000001 0.160180 -0.987087 0.000000 0.160183 -1.000000 0.000000 -0.000000 -0.987088 0.000001 0.160180 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987087 0.000000 0.160183 --1.000000 0.000000 0.000000 --0.987087 0.000000 0.160183 --0.987087 0.000000 0.160183 --1.000000 0.000000 0.000000 --0.987087 0.000000 0.160183 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.987396 0.000000 0.158268 -0.987396 0.000000 0.158268 -0.709857 0.000000 0.704345 -0.709857 0.000000 0.704345 -0.709858 0.000000 0.704345 -0.987396 0.000000 0.158268 -0.000000 0.000000 1.000000 -0.000000 -0.162115 0.986772 -0.018551 -0.170483 0.985186 -0.000000 0.000000 1.000000 -0.018551 -0.170483 0.985186 -0.173478 -0.024209 0.984540 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.173478 -0.024209 0.984540 -0.000000 0.000000 1.000000 -0.173478 -0.024209 0.984540 -0.162115 0.000000 0.986772 -0.173478 -0.024209 0.984540 -0.018551 -0.170483 0.985186 -0.155927 -0.141040 0.977647 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 -0.162115 0.986772 -0.000000 -0.162115 0.986772 -0.000000 -0.162115 0.986772 -0.000000 0.000000 1.000000 -0.999195 0.000000 -0.040116 -0.999195 -0.000000 -0.040116 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999195 0.000000 -0.040116 -0.999799 0.000000 -0.020062 -1.000000 -0.000000 0.000001 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000001 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999195 0.000000 -0.040118 -0.999195 0.000000 -0.040117 -0.985934 -0.159933 -0.048522 -0.985934 -0.159933 -0.048522 -0.985935 -0.159933 -0.048523 -0.999195 0.000000 -0.040118 -0.974743 -0.158179 0.157659 -0.987087 -0.160182 0.000001 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.987396 0.000000 0.158268 -0.974743 -0.158179 0.157659 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000001 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -1.000000 0.000000 0.000001 -0.999799 0.000000 -0.020062 -0.999195 0.000000 -0.040117 -0.999195 0.000000 -0.040116 -0.999195 0.000000 -0.040116 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999195 -0.000000 -0.040116 -0.999195 -0.000001 -0.040116 -0.999799 -0.000000 -0.020062 -0.999799 -0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999195 -0.000000 -0.040116 -0.999799 -0.000000 -0.020062 -1.000000 -0.000000 0.000001 -1.000000 -0.000000 0.000001 -1.000000 -0.000000 0.000001 -0.999799 0.000000 -0.020062 -0.999799 -0.000000 -0.020062 -1.000000 0.000000 0.000000 -1.000000 -0.000000 0.000001 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000000 -0.999195 -0.000001 -0.040116 -0.999195 -0.000005 -0.040120 -0.999196 -0.000000 -0.040096 -0.999196 -0.000000 -0.040096 -0.999196 -0.000000 -0.040095 -0.999195 -0.000001 -0.040116 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000000 -0.987087 -0.160182 0.000001 -0.987087 -0.160182 0.000001 -0.987087 -0.160182 0.000000 -1.000000 0.000000 0.000001 -0.987087 -0.160182 0.000000 -0.987087 -0.160182 0.000001 -0.707107 -0.707107 0.000000 -0.707107 -0.707107 0.000000 -0.707107 -0.707107 0.000001 -0.987087 -0.160182 0.000000 -0.707107 -0.707107 0.000001 -0.707107 -0.707107 0.000000 -0.160182 -0.987087 0.000000 -0.160182 -0.987087 0.000000 -0.160183 -0.987087 0.000000 -0.707107 -0.707107 0.000001 -0.160183 -0.987087 0.000000 -0.160182 -0.987087 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.160183 -0.987087 0.000000 -1.000000 0.000000 0.000001 -0.987087 -0.160182 0.000000 -0.986399 -0.162556 -0.024328 -0.986399 -0.162556 -0.024328 -0.999799 0.000000 -0.020062 -1.000000 0.000000 0.000001 -0.986399 -0.162556 -0.024328 -0.987087 -0.160182 0.000000 -0.707107 -0.707107 0.000001 -0.707107 -0.707107 0.000001 -0.705633 -0.707781 -0.033587 -0.986399 -0.162556 -0.024328 -0.705633 -0.707781 -0.033587 -0.707107 -0.707107 0.000001 -0.160183 -0.987087 0.000000 -0.160183 -0.987087 0.000000 -0.161626 -0.986374 -0.030703 -0.705633 -0.707781 -0.033587 -0.000000 -0.999611 -0.027908 -0.000000 -0.999610 -0.027908 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.999611 -0.027908 -0.000001 -0.998442 -0.055795 -0.000000 -0.999611 -0.027908 -0.000000 -0.999610 -0.027908 -0.000000 -0.999610 -0.027908 --0.000001 -0.998442 -0.055795 -0.000001 -0.998442 -0.055795 -0.000000 -0.999610 -0.027908 -0.000000 -0.999611 -0.027908 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.999610 -0.027908 -0.161626 -0.986374 -0.030703 -0.160183 -0.987087 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.999610 -0.027908 -0.161626 -0.986374 -0.030703 -0.159831 -0.985228 -0.061474 -0.000000 -0.998442 -0.055795 -0.000000 -0.998442 -0.055794 -0.000000 -0.998442 -0.055794 -0.159831 -0.985228 -0.061474 -0.159831 -0.985228 -0.061474 -0.000000 -0.999610 -0.027908 -0.000000 -0.998442 -0.055795 -0.159831 -0.985228 -0.061474 -0.159831 -0.985228 -0.061474 -0.161626 -0.986374 -0.030703 -0.000000 -0.999610 -0.027908 -0.161626 -0.986374 -0.030703 -0.159831 -0.985228 -0.061474 -0.705588 -0.705376 -0.067746 -0.705588 -0.705376 -0.067746 -0.705633 -0.707781 -0.033587 -0.161626 -0.986374 -0.030703 -0.705588 -0.705376 -0.067746 -0.985934 -0.159933 -0.048522 -0.986399 -0.162556 -0.024328 -0.986399 -0.162556 -0.024328 -0.705633 -0.707781 -0.033587 -0.705588 -0.705376 -0.067746 -0.999195 0.000000 -0.040117 -0.999799 0.000000 -0.020062 -0.986399 -0.162556 -0.024328 -0.986399 -0.162556 -0.024328 -0.985934 -0.159933 -0.048522 -0.999195 0.000000 -0.040117 -0.999195 0.000000 -0.040118 -0.985935 -0.159933 -0.048523 -0.902713 -0.144766 -0.405157 -0.902713 -0.144766 -0.405157 -0.911793 0.000000 -0.410650 -0.999195 0.000000 -0.040118 -0.985935 -0.159933 -0.048523 -0.705588 -0.705377 -0.067746 -0.645117 -0.643053 -0.412683 -0.645117 -0.643053 -0.412683 -0.902713 -0.144766 -0.405157 -0.985935 -0.159933 -0.048523 -0.645117 -0.643053 -0.412683 -0.705588 -0.705377 -0.067746 -0.159831 -0.985228 -0.061474 -0.159831 -0.985228 -0.061474 -0.144762 -0.898824 -0.413714 -0.645117 -0.643053 -0.412683 -0.144762 -0.898824 -0.413714 -0.159831 -0.985228 -0.061474 -0.000000 -0.998442 -0.055794 -0.000000 -0.998442 -0.055794 -0.000000 -0.906973 -0.421189 -0.144762 -0.898824 -0.413714 --0.000000 -0.998441 -0.055810 -0.000005 -0.998442 -0.055795 -0.000001 -0.999610 -0.027908 -0.000001 -0.999610 -0.027908 -0.000000 -0.999611 -0.027905 --0.000000 -0.998441 -0.055810 -0.000000 -0.987396 0.158267 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.987396 0.158267 -0.000000 -0.987396 0.158267 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000001 -0.999610 -0.027908 -0.000001 -0.999610 -0.027908 -0.000000 -0.999610 -0.027908 -0.000000 -1.000000 0.000000 -0.000001 -0.999610 -0.027908 -0.000005 -0.998442 -0.055795 --0.000001 -0.998442 -0.055795 --0.000001 -0.998442 -0.055795 -0.000000 -0.999610 -0.027908 -0.000001 -0.999610 -0.027908 -0.000002 -0.998442 -0.055798 -0.000005 -0.998442 -0.055795 --0.000000 -0.998441 -0.055810 --0.000000 -0.998441 -0.055810 --0.000000 -0.998441 -0.055815 -0.000002 -0.998442 -0.055798 -0.000002 -0.998442 -0.055798 --0.000000 -0.998441 -0.055815 -0.000000 -0.906973 -0.421189 -0.000000 -0.906973 -0.421189 -0.000000 -0.906973 -0.421189 -0.000002 -0.998442 -0.055798 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.999611 -0.027905 -0.000000 -0.999611 -0.027905 -0.000001 -0.999610 -0.027908 -0.000000 -1.000000 0.000000 -0.987396 0.000000 0.158268 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000001 -0.987396 0.000000 0.158268 -0.987396 0.000000 0.158268 -0.999195 -0.000001 -0.040116 -0.999196 -0.000000 -0.040095 -0.999799 0.000000 -0.020063 -0.999799 0.000000 -0.020063 -0.999799 -0.000000 -0.020062 -0.999195 -0.000001 -0.040116 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000001 -1.000000 0.000000 -0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000001 -1.000000 0.000000 -0.000001 -1.000000 0.000000 -0.000001 -1.000000 0.000000 -0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000001 -1.000000 0.000000 -0.000001 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000001 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000001 -0.000000 -1.000000 -0.000001 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 -0.000000 --0.000000 -1.000000 0.000003 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000001 --0.000000 -1.000000 0.000000 --0.000000 -1.000000 0.000003 --0.000000 -1.000000 0.000003 -0.000000 -1.000000 0.000021 --0.000000 -1.000000 0.000001 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.293667 -0.950362 -0.102818 --0.437377 -0.898427 0.039117 --0.466777 -0.877351 -0.111237 --0.466777 -0.877351 -0.111237 -0.378489 -0.922436 0.076533 -0.293667 -0.950362 -0.102818 -0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.053947 -0.933079 -0.355603 -0.053947 -0.933079 -0.355603 -0.000000 -0.928568 -0.371161 -0.000000 -1.000000 0.000002 --0.083860 -0.883048 -0.461729 -0.058021 -0.917041 0.394549 -0.219047 -0.944662 0.244197 -0.219047 -0.944662 0.244197 --0.334821 -0.862577 -0.379284 --0.083860 -0.883048 -0.461729 --0.278630 -0.944534 0.173843 -0.199706 -0.956891 -0.210898 -0.126855 -0.942566 -0.308994 -0.126855 -0.942566 -0.308994 --0.204871 -0.931518 0.300504 --0.278630 -0.944534 0.173843 --0.437377 -0.898427 0.039117 -0.293667 -0.950362 -0.102818 -0.199706 -0.956891 -0.210898 -0.199706 -0.956891 -0.210898 --0.278630 -0.944534 0.173843 --0.437377 -0.898427 0.039117 -0.000000 -0.902777 -0.430109 --0.000000 -0.903393 0.428813 -0.058021 -0.917041 0.394549 -0.058021 -0.917041 0.394549 --0.083860 -0.883048 -0.461729 -0.000000 -0.902777 -0.430109 -0.219047 -0.944662 0.244197 -0.378489 -0.922436 0.076533 --0.466777 -0.877351 -0.111237 --0.466777 -0.877351 -0.111237 --0.334821 -0.862577 -0.379284 -0.219047 -0.944662 0.244197 --0.204871 -0.931518 0.300504 -0.126855 -0.942566 -0.308994 -0.053947 -0.933079 -0.355603 -0.053947 -0.933079 -0.355603 -0.000000 -1.000000 0.000002 --0.204871 -0.931518 0.300504 -0.984855 -0.000001 0.173380 -0.973923 0.000000 -0.226877 -0.906193 -0.386267 -0.172082 -0.906193 -0.386267 -0.172082 -0.924386 -0.345298 0.162108 -0.984855 -0.000001 0.173380 --0.965948 0.000000 0.258737 --0.972507 0.000000 -0.232874 --0.922754 -0.317517 -0.218422 --0.922754 -0.317517 -0.218422 --0.876796 -0.404449 0.260095 --0.965948 0.000000 0.258737 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 0.000000 1.000000 -0.165253 0.000000 -0.986251 -0.000000 0.000000 -1.000000 -0.000000 -0.389580 -0.920992 -0.000000 -0.389580 -0.920992 -0.145080 -0.399992 -0.904963 -0.165253 0.000000 -0.986251 --0.661497 0.000000 -0.749948 --0.174458 0.000000 -0.984665 --0.161327 -0.320071 -0.933557 --0.161327 -0.320071 -0.933557 --0.628453 -0.312262 -0.712418 --0.661497 0.000000 -0.749948 -0.139943 0.000000 0.990160 -0.682763 -0.000001 0.730640 -0.629331 -0.383170 0.676109 -0.629331 -0.383170 0.676109 -0.134000 -0.341445 0.930301 -0.139943 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 0.000000 1.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 --0.865983 0.000000 -0.500074 --0.472044 -0.840449 -0.266121 --0.472044 -0.840449 -0.266121 -0.000001 -0.480135 -0.877194 -0.000000 0.000000 -1.000000 -0.973923 0.000000 -0.226877 -0.766123 0.000000 -0.642694 -0.686198 -0.460064 -0.563448 -0.686198 -0.460064 -0.563448 -0.906193 -0.386267 -0.172082 -0.973923 0.000000 -0.226877 --0.865983 0.000000 -0.500074 --0.965948 0.000000 0.258737 --0.876796 -0.404449 0.260095 --0.876796 -0.404449 0.260095 --0.472044 -0.840449 -0.266121 --0.865983 0.000000 -0.500074 --0.000000 0.000000 1.000000 -0.139943 0.000000 0.990160 -0.134000 -0.341445 0.930301 -0.134000 -0.341445 0.930301 --0.000000 -0.335574 0.942014 --0.000000 0.000000 1.000000 --0.174458 0.000000 -0.984665 -0.000000 0.000000 -1.000000 --0.000000 -0.335182 -0.942154 --0.000000 -0.335182 -0.942154 --0.161327 -0.320071 -0.933557 --0.174458 0.000000 -0.984665 --0.972507 0.000000 -0.232874 --0.661497 0.000000 -0.749948 --0.628453 -0.312262 -0.712418 --0.628453 -0.312262 -0.712418 --0.922754 -0.317517 -0.218422 --0.972507 0.000000 -0.232874 -0.682763 -0.000001 0.730640 -0.984855 -0.000001 0.173380 -0.924386 -0.345298 0.162108 -0.924386 -0.345298 0.162108 -0.629331 -0.383170 0.676109 -0.682763 -0.000001 0.730640 -0.446772 0.000000 -0.894648 -0.165253 0.000000 -0.986251 -0.145080 -0.399992 -0.904963 -0.145080 -0.399992 -0.904963 -0.391985 -0.437360 -0.809360 -0.446772 0.000000 -0.894648 -0.766123 0.000000 -0.642694 -0.446772 0.000000 -0.894648 -0.391985 -0.437360 -0.809360 -0.391985 -0.437360 -0.809360 -0.686198 -0.460064 -0.563448 -0.766123 0.000000 -0.642694 --0.437377 -0.898427 0.039117 --0.876796 -0.404449 0.260095 --0.922754 -0.317517 -0.218422 --0.922754 -0.317517 -0.218422 --0.466777 -0.877351 -0.111237 --0.437377 -0.898427 0.039117 -0.378489 -0.922436 0.076533 -0.924386 -0.345298 0.162108 -0.906193 -0.386267 -0.172082 -0.906193 -0.386267 -0.172082 -0.293667 -0.950362 -0.102818 -0.378489 -0.922436 0.076533 -0.000000 -0.960502 0.278273 --0.016761 -0.961573 0.274037 -0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.000000 -0.960502 0.278273 -0.145080 -0.399992 -0.904963 -0.000000 -0.389580 -0.920992 -0.000000 -0.928568 -0.371161 -0.000000 -0.928568 -0.371161 -0.053947 -0.933079 -0.355603 -0.145080 -0.399992 -0.904963 -0.058021 -0.917041 0.394549 -0.134000 -0.341445 0.930301 -0.629331 -0.383170 0.676109 -0.629331 -0.383170 0.676109 -0.219047 -0.944662 0.244197 -0.058021 -0.917041 0.394549 --0.334821 -0.862577 -0.379284 --0.628453 -0.312262 -0.712418 --0.161327 -0.320071 -0.933557 --0.161327 -0.320071 -0.933557 --0.083860 -0.883048 -0.461729 --0.334821 -0.862577 -0.379284 -0.199706 -0.956891 -0.210898 -0.686198 -0.460064 -0.563448 -0.391985 -0.437360 -0.809360 -0.391985 -0.437360 -0.809360 -0.126855 -0.942566 -0.308994 -0.199706 -0.956891 -0.210898 -0.293667 -0.950362 -0.102818 -0.906193 -0.386267 -0.172082 -0.686198 -0.460064 -0.563448 -0.686198 -0.460064 -0.563448 -0.199706 -0.956891 -0.210898 -0.293667 -0.950362 -0.102818 --0.278630 -0.944534 0.173843 --0.472044 -0.840449 -0.266121 --0.876796 -0.404449 0.260095 --0.876796 -0.404449 0.260095 --0.437377 -0.898427 0.039117 --0.278630 -0.944534 0.173843 --0.000000 -0.903393 0.428813 --0.000000 -0.335574 0.942014 -0.134000 -0.341445 0.930301 -0.134000 -0.341445 0.930301 -0.058021 -0.917041 0.394549 --0.000000 -0.903393 0.428813 --0.161327 -0.320071 -0.933557 --0.000000 -0.335182 -0.942154 -0.000000 -0.902777 -0.430109 -0.000000 -0.902777 -0.430109 --0.083860 -0.883048 -0.461729 --0.161327 -0.320071 -0.933557 -0.629331 -0.383170 0.676109 -0.924386 -0.345298 0.162108 -0.378489 -0.922436 0.076533 -0.378489 -0.922436 0.076533 -0.219047 -0.944662 0.244197 -0.629331 -0.383170 0.676109 --0.922754 -0.317517 -0.218422 --0.628453 -0.312262 -0.712418 --0.334821 -0.862577 -0.379284 --0.334821 -0.862577 -0.379284 --0.466777 -0.877351 -0.111237 --0.922754 -0.317517 -0.218422 -0.126855 -0.942566 -0.308994 -0.391985 -0.437360 -0.809360 -0.145080 -0.399992 -0.904963 -0.145080 -0.399992 -0.904963 -0.053947 -0.933079 -0.355603 -0.126855 -0.942566 -0.308994 --0.204871 -0.931518 0.300504 --0.016761 -0.961573 0.274037 --0.472044 -0.840449 -0.266121 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 --0.016761 -0.961573 0.274037 --0.016761 -0.961573 0.274037 -0.000000 -0.960502 0.278273 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.999997 -0.002593 -0.000000 -0.999997 -0.002593 --0.016761 -0.961573 0.274037 -0.000000 -0.482408 0.875946 --0.016761 -0.961573 0.274037 --0.204871 -0.931518 0.300504 -0.000000 -1.000000 0.000002 --0.204871 -0.931518 0.300504 --0.472044 -0.840449 -0.266121 --0.278630 -0.944534 0.173843 -0.000001 -0.480135 -0.877194 --0.472044 -0.840449 -0.266121 --0.016761 -0.961573 0.274037 --0.016761 -0.961573 0.274037 -0.000000 -0.999997 -0.002593 -0.000001 -0.480135 -0.877194 --0.293669 -0.950361 -0.102818 --0.378490 -0.922436 0.076533 -0.466777 -0.877352 -0.111236 -0.466777 -0.877352 -0.111236 -0.437376 -0.898427 0.039117 --0.293669 -0.950361 -0.102818 -0.000000 -1.000000 0.000002 -0.000000 -0.928568 -0.371161 --0.053947 -0.933079 -0.355603 --0.053947 -0.933079 -0.355603 -0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.083860 -0.883048 -0.461729 -0.334821 -0.862576 -0.379284 --0.219047 -0.944662 0.244197 --0.219047 -0.944662 0.244197 --0.058021 -0.917041 0.394549 -0.083860 -0.883048 -0.461729 -0.278630 -0.944534 0.173843 -0.204871 -0.931518 0.300504 --0.126855 -0.942566 -0.308994 --0.126855 -0.942566 -0.308994 --0.199706 -0.956891 -0.210898 -0.278630 -0.944534 0.173843 -0.437376 -0.898427 0.039117 -0.278630 -0.944534 0.173843 --0.199706 -0.956891 -0.210898 --0.199706 -0.956891 -0.210898 --0.293669 -0.950361 -0.102818 -0.437376 -0.898427 0.039117 -0.000000 -0.902777 -0.430109 -0.083860 -0.883048 -0.461729 --0.058021 -0.917041 0.394549 --0.058021 -0.917041 0.394549 --0.000000 -0.903393 0.428813 -0.000000 -0.902777 -0.430109 --0.219047 -0.944662 0.244197 -0.334821 -0.862576 -0.379284 -0.466777 -0.877352 -0.111236 -0.466777 -0.877352 -0.111236 --0.378490 -0.922436 0.076533 --0.219047 -0.944662 0.244197 -0.204871 -0.931518 0.300504 -0.000000 -1.000000 0.000002 --0.053947 -0.933079 -0.355603 --0.053947 -0.933079 -0.355603 --0.126855 -0.942566 -0.308994 -0.204871 -0.931518 0.300504 --0.984855 0.000000 0.173382 --0.924387 -0.345297 0.162109 --0.906194 -0.386265 -0.172082 --0.906194 -0.386265 -0.172082 --0.973923 0.000000 -0.226877 --0.984855 0.000000 0.173382 -0.965948 0.000000 0.258737 -0.876797 -0.404449 0.260094 -0.922754 -0.317518 -0.218422 -0.922754 -0.317518 -0.218422 -0.972507 0.000000 -0.232875 -0.965948 0.000000 0.258737 -0.000000 0.000000 1.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.165253 0.000000 -0.986251 --0.145080 -0.399992 -0.904963 -0.000000 -0.389580 -0.920992 -0.000000 -0.389580 -0.920992 -0.000000 0.000000 -1.000000 --0.165253 0.000000 -0.986251 -0.661497 0.000000 -0.749948 -0.628453 -0.312262 -0.712418 -0.161327 -0.320071 -0.933557 -0.161327 -0.320071 -0.933557 -0.174458 0.000000 -0.984665 -0.661497 0.000000 -0.749948 --0.139942 0.000000 0.990160 --0.133999 -0.341445 0.930301 --0.629331 -0.383170 0.676109 --0.629331 -0.383170 0.676109 --0.682761 0.000000 0.730642 --0.139942 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 --0.000001 -0.480135 -0.877194 -0.472044 -0.840449 -0.266122 -0.472044 -0.840449 -0.266122 -0.865983 0.000000 -0.500074 -0.000000 0.000000 -1.000000 --0.973923 0.000000 -0.226877 --0.906194 -0.386265 -0.172082 --0.686198 -0.460063 -0.563448 --0.686198 -0.460063 -0.563448 --0.766123 0.000000 -0.642694 --0.973923 0.000000 -0.226877 -0.865983 0.000000 -0.500074 -0.472044 -0.840449 -0.266122 -0.876797 -0.404449 0.260094 -0.876797 -0.404449 0.260094 -0.965948 0.000000 0.258737 -0.865983 0.000000 -0.500074 --0.000000 0.000000 1.000000 --0.000000 -0.335574 0.942014 --0.133999 -0.341445 0.930301 --0.133999 -0.341445 0.930301 --0.139942 0.000000 0.990160 --0.000000 0.000000 1.000000 -0.174458 0.000000 -0.984665 -0.161327 -0.320071 -0.933557 --0.000000 -0.335182 -0.942154 --0.000000 -0.335182 -0.942154 -0.000000 0.000000 -1.000000 -0.174458 0.000000 -0.984665 -0.972507 0.000000 -0.232875 -0.922754 -0.317518 -0.218422 -0.628453 -0.312262 -0.712418 -0.628453 -0.312262 -0.712418 -0.661497 0.000000 -0.749948 -0.972507 0.000000 -0.232875 --0.682761 0.000000 0.730642 --0.629331 -0.383170 0.676109 --0.924387 -0.345297 0.162109 --0.924387 -0.345297 0.162109 --0.984855 0.000000 0.173382 --0.682761 0.000000 0.730642 --0.446771 0.000000 -0.894648 --0.391985 -0.437360 -0.809361 --0.145080 -0.399992 -0.904963 --0.145080 -0.399992 -0.904963 --0.165253 0.000000 -0.986251 --0.446771 0.000000 -0.894648 --0.766123 0.000000 -0.642694 --0.686198 -0.460063 -0.563448 --0.391985 -0.437360 -0.809361 --0.391985 -0.437360 -0.809361 --0.446771 0.000000 -0.894648 --0.766123 0.000000 -0.642694 -0.437376 -0.898427 0.039117 -0.466777 -0.877352 -0.111236 -0.922754 -0.317518 -0.218422 -0.922754 -0.317518 -0.218422 -0.876797 -0.404449 0.260094 -0.437376 -0.898427 0.039117 --0.378490 -0.922436 0.076533 --0.293669 -0.950361 -0.102818 --0.906194 -0.386265 -0.172082 --0.906194 -0.386265 -0.172082 --0.924387 -0.345297 0.162109 --0.378490 -0.922436 0.076533 -0.000000 -0.960502 0.278273 -0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.000000 -1.000000 0.000002 -0.016761 -0.961573 0.274037 -0.000000 -0.960502 0.278273 --0.145080 -0.399992 -0.904963 --0.053947 -0.933079 -0.355603 -0.000000 -0.928568 -0.371161 -0.000000 -0.928568 -0.371161 -0.000000 -0.389580 -0.920992 --0.145080 -0.399992 -0.904963 --0.058021 -0.917041 0.394549 --0.219047 -0.944662 0.244197 --0.629331 -0.383170 0.676109 --0.629331 -0.383170 0.676109 --0.133999 -0.341445 0.930301 --0.058021 -0.917041 0.394549 -0.334821 -0.862576 -0.379284 -0.083860 -0.883048 -0.461729 -0.161327 -0.320071 -0.933557 -0.161327 -0.320071 -0.933557 -0.628453 -0.312262 -0.712418 -0.334821 -0.862576 -0.379284 --0.199706 -0.956891 -0.210898 --0.126855 -0.942566 -0.308994 --0.391985 -0.437360 -0.809361 --0.391985 -0.437360 -0.809361 --0.686198 -0.460063 -0.563448 --0.199706 -0.956891 -0.210898 --0.293669 -0.950361 -0.102818 --0.199706 -0.956891 -0.210898 --0.686198 -0.460063 -0.563448 --0.686198 -0.460063 -0.563448 --0.906194 -0.386265 -0.172082 --0.293669 -0.950361 -0.102818 -0.278630 -0.944534 0.173843 -0.437376 -0.898427 0.039117 -0.876797 -0.404449 0.260094 -0.876797 -0.404449 0.260094 -0.472044 -0.840449 -0.266122 -0.278630 -0.944534 0.173843 --0.000000 -0.903393 0.428813 --0.058021 -0.917041 0.394549 --0.133999 -0.341445 0.930301 --0.133999 -0.341445 0.930301 --0.000000 -0.335574 0.942014 --0.000000 -0.903393 0.428813 -0.161327 -0.320071 -0.933557 -0.083860 -0.883048 -0.461729 -0.000000 -0.902777 -0.430109 -0.000000 -0.902777 -0.430109 --0.000000 -0.335182 -0.942154 -0.161327 -0.320071 -0.933557 --0.629331 -0.383170 0.676109 --0.219047 -0.944662 0.244197 --0.378490 -0.922436 0.076533 --0.378490 -0.922436 0.076533 --0.924387 -0.345297 0.162109 --0.629331 -0.383170 0.676109 -0.922754 -0.317518 -0.218422 -0.466777 -0.877352 -0.111236 -0.334821 -0.862576 -0.379284 -0.334821 -0.862576 -0.379284 -0.628453 -0.312262 -0.712418 -0.922754 -0.317518 -0.218422 --0.126855 -0.942566 -0.308994 --0.053947 -0.933079 -0.355603 --0.145080 -0.399992 -0.904963 --0.145080 -0.399992 -0.904963 --0.391985 -0.437360 -0.809361 --0.126855 -0.942566 -0.308994 -0.204871 -0.931518 0.300504 -0.472044 -0.840449 -0.266122 -0.016761 -0.961573 0.274037 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.000000 -0.482408 0.875946 -0.000000 -0.960502 0.278273 -0.016761 -0.961573 0.274037 -0.016761 -0.961573 0.274037 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.016761 -0.961573 0.274037 -0.000000 -0.999997 -0.002593 -0.000000 -0.999997 -0.002593 -0.000000 -0.482408 0.875946 -0.000000 -0.482408 0.875946 -0.016761 -0.961573 0.274037 -0.000000 -1.000000 0.000002 -0.204871 -0.931518 0.300504 -0.204871 -0.931518 0.300504 -0.278630 -0.944534 0.173843 -0.472044 -0.840449 -0.266122 --0.000001 -0.480135 -0.877194 -0.000000 -0.999997 -0.002593 -0.016761 -0.961573 0.274037 -0.016761 -0.961573 0.274037 -0.472044 -0.840449 -0.266122 --0.000001 -0.480135 -0.877194 --0.159831 0.985228 -0.061474 --0.159831 0.985228 -0.061474 --0.705588 0.705377 -0.067746 --0.705588 0.705377 -0.067746 --0.705588 0.705376 -0.067746 --0.159831 0.985228 -0.061474 --0.987087 0.160182 0.000001 --0.974743 0.158179 0.157659 --0.700073 0.696893 0.155683 --0.700073 0.696893 0.155683 --0.707107 0.707107 0.000000 --0.987087 0.160182 0.000001 --0.705588 0.705377 -0.067746 --0.985934 0.159934 -0.048521 --0.985934 0.159934 -0.048521 --0.985934 0.159934 -0.048521 --0.705588 0.705376 -0.067746 --0.705588 0.705377 -0.067746 --0.707107 0.707107 0.000000 --0.700073 0.696893 0.155683 --0.155746 0.975487 0.155460 --0.155746 0.975487 0.155460 --0.160182 0.987087 0.000000 --0.707107 0.707107 0.000000 --0.155928 0.141040 0.977647 --0.018551 0.170483 0.985186 --0.107470 0.721820 0.683686 --0.107470 0.721820 0.683686 --0.541660 0.532699 0.650258 --0.155928 0.141040 0.977647 --0.173478 0.024209 0.984540 --0.155928 0.141040 0.977647 --0.541660 0.532699 0.650258 --0.541660 0.532699 0.650258 --0.720099 0.114166 0.684415 --0.173478 0.024209 0.984540 --0.541660 0.532699 0.650258 --0.107470 0.721820 0.683686 --0.155746 0.975487 0.155460 --0.155746 0.975487 0.155460 --0.700073 0.696893 0.155683 --0.541660 0.532699 0.650258 --0.720099 0.114166 0.684415 --0.541660 0.532699 0.650258 --0.700073 0.696893 0.155683 --0.700073 0.696893 0.155683 --0.974743 0.158179 0.157659 --0.720099 0.114166 0.684415 --0.902713 0.144766 -0.405157 --0.645117 0.643053 -0.412683 --0.456612 0.453865 -0.765188 --0.456612 0.453865 -0.765188 --0.676471 0.107125 -0.728637 --0.902713 0.144766 -0.405157 --0.456612 0.453865 -0.765188 --0.645117 0.643053 -0.412683 --0.144762 0.898824 -0.413714 --0.144762 0.898824 -0.413714 --0.107386 0.671902 -0.732814 --0.456612 0.453865 -0.765188 --0.676471 0.107125 -0.728637 --0.692241 0.000000 -0.721666 --0.911793 0.000000 -0.410650 --0.911793 0.000000 -0.410650 --0.902713 0.144766 -0.405157 --0.676471 0.107125 -0.728637 --0.911793 0.000000 -0.410650 --0.911793 0.000000 -0.410650 --0.692241 0.000000 -0.721666 --0.692241 0.000000 -0.721666 --0.692242 0.000000 -0.721666 --0.911793 0.000000 -0.410650 -0.000000 -0.987088 -0.160182 -0.000000 -0.986432 -0.164170 -0.000000 -1.000000 0.000000 -0.000000 -0.987088 -0.160182 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.987088 -0.160182 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.986432 -0.164170 -0.000000 -0.987088 -0.160182 -0.000000 -0.707108 -0.707105 -0.000000 -0.707108 -0.707105 -0.000000 -0.701326 -0.712841 -0.000000 -0.986432 -0.164170 -0.000000 -0.701326 -0.712841 -0.000000 -0.707108 -0.707105 -0.000000 -0.160184 -0.987087 -0.000000 -0.160184 -0.987087 -0.000000 -0.159534 -0.987192 -0.000000 -0.701326 -0.712841 -0.000000 -0.159534 -0.987192 -0.000000 -0.160184 -0.987087 --0.000000 0.160184 -0.987087 --0.000000 0.160184 -0.987087 --0.000000 0.159534 -0.987193 -0.000000 -0.159534 -0.987192 --0.000000 0.160184 -0.987087 --0.000000 0.707107 -0.707106 --0.000000 0.701324 -0.712842 --0.000000 0.701324 -0.712842 --0.000000 0.159534 -0.987193 --0.000000 0.160184 -0.987087 --0.000000 0.707107 -0.707106 --0.000000 0.987087 -0.160183 --0.000000 0.986432 -0.164171 --0.000000 0.986432 -0.164171 --0.000000 0.701324 -0.712842 --0.000000 0.707107 -0.707106 -0.000000 0.686823 -0.726825 -0.000000 0.906973 -0.421189 -0.000000 0.906973 -0.421189 -0.000000 0.906973 -0.421189 -0.000000 0.686823 -0.726825 -0.000000 0.686823 -0.726825 -0.000000 0.906973 -0.421189 -0.000000 0.686823 -0.726825 --0.107386 0.671902 -0.732814 --0.107386 0.671902 -0.732814 --0.144762 0.898824 -0.413714 -0.000000 0.906973 -0.421189 -0.160183 0.000000 -0.987087 -0.707108 0.000000 -0.707105 -0.699024 0.000000 -0.715099 -0.699024 0.000000 -0.715099 -0.159277 0.000000 -0.987234 -0.160183 0.000000 -0.987087 -0.707108 0.000000 -0.707105 -0.987088 0.000000 -0.160182 -0.986171 0.000000 -0.165731 -0.986171 0.000000 -0.165731 -0.699024 0.000000 -0.715099 -0.707108 0.000000 -0.707105 --0.987088 -0.000000 -0.160181 --0.986171 -0.000000 -0.165730 --1.000000 -0.000000 0.000000 --0.987088 -0.000000 -0.160181 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --0.987088 -0.000000 -0.160181 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --0.986171 -0.000000 -0.165730 --0.987088 -0.000000 -0.160181 --0.707109 -0.000000 -0.707105 --0.707109 -0.000000 -0.707105 --0.699024 -0.000000 -0.715098 --0.986171 -0.000000 -0.165730 --0.699024 -0.000000 -0.715098 --0.707109 -0.000000 -0.707105 --0.160184 -0.000000 -0.987087 --0.160184 -0.000000 -0.987087 --0.159277 -0.000000 -0.987234 --0.699024 -0.000000 -0.715098 --0.159277 -0.000000 -0.987234 --0.160184 -0.000000 -0.987087 -0.160183 0.000000 -0.987087 -0.160183 0.000000 -0.987087 -0.159277 0.000000 -0.987234 --0.159277 -0.000000 -0.987234 --0.987396 0.000000 0.158268 --0.709858 0.000000 0.704345 --0.720099 0.114166 0.684415 --0.720099 0.114166 0.684415 --0.974743 0.158179 0.157659 --0.987396 0.000000 0.158268 --0.709858 0.000000 0.704345 --0.162115 0.000000 0.986772 --0.173478 0.024209 0.984540 --0.173478 0.024209 0.984540 --0.720099 0.114166 0.684415 --0.709858 0.000000 0.704345 --0.162115 0.000000 0.986772 --0.709857 0.000000 0.704345 --0.709857 0.000000 0.704345 --0.709857 0.000000 0.704345 --0.162115 0.000000 0.986772 --0.162115 0.000000 0.986772 -0.000000 0.707107 0.707106 --0.000000 0.707109 0.707105 --0.000000 0.987088 0.160181 --0.000000 0.987088 0.160181 -0.000001 0.987087 0.160183 -0.000000 0.707107 0.707106 --0.000000 0.160184 0.987087 --0.000000 0.707109 0.707105 -0.000000 0.707107 0.707106 -0.000000 0.707107 0.707106 --0.000000 0.160183 0.987087 --0.000000 0.160184 0.987087 -0.000000 -0.160183 0.987087 --0.000000 0.160184 0.987087 --0.000000 0.160183 0.987087 --0.000000 0.160183 0.987087 -0.000000 -0.160183 0.987087 -0.000000 -0.160183 0.987087 -0.000000 -0.707107 0.707106 -0.000000 -0.160183 0.987087 -0.000000 -0.160183 0.987087 -0.000000 -0.160183 0.987087 -0.000000 -0.707107 0.707106 -0.000000 -0.707107 0.707106 -0.000001 -0.987087 0.160183 -0.000000 -0.707107 0.707106 -0.000000 -0.707107 0.707106 -0.000000 -0.707107 0.707106 -0.000001 -0.987087 0.160183 -0.000001 -0.987087 0.160183 -0.000000 0.987396 0.158267 -0.000000 0.987396 0.158267 -0.000000 0.709859 0.704344 -0.000000 0.709859 0.704344 -0.000000 0.709859 0.704344 -0.000000 0.987396 0.158267 -0.000000 0.709859 0.704344 -0.000000 0.709859 0.704344 -0.000000 0.162115 0.986772 -0.000000 0.162115 0.986772 -0.000000 0.162115 0.986772 -0.000000 0.709859 0.704344 -0.000000 0.987396 0.158267 --0.155746 0.975487 0.155460 --0.107470 0.721820 0.683686 --0.107470 0.721820 0.683686 -0.000000 0.709858 0.704344 -0.000000 0.987396 0.158267 --0.018551 0.170483 0.985186 -0.000000 0.162115 0.986772 -0.000000 0.709858 0.704344 -0.000000 0.709858 0.704344 --0.107470 0.721820 0.683686 --0.018551 0.170483 0.985186 -0.160184 0.000000 0.987087 -0.707107 0.000000 0.707107 -0.707107 0.000000 0.707107 -0.707107 0.000000 0.707107 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 --0.160184 -0.000000 0.987087 --0.160184 -0.000000 0.987087 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 --0.160184 -0.000000 0.987087 --0.707108 -0.000001 0.707105 --0.160184 -0.000000 0.987087 --0.160184 -0.000000 0.987087 --0.160184 -0.000000 0.987087 --0.707108 0.000000 0.707106 --0.707108 -0.000001 0.707105 --0.987087 -0.000000 0.160183 --0.987088 -0.000001 0.160181 --0.707108 -0.000001 0.707105 --0.707108 -0.000001 0.707105 --0.707108 0.000000 0.707106 --0.987087 -0.000000 0.160183 -0.707107 0.000000 0.707107 -0.987087 0.000000 0.160183 -0.987087 0.000000 0.160183 -0.987087 0.000000 0.160183 -0.707107 0.000000 0.707107 -0.707107 0.000000 0.707107 --0.911793 0.000000 -0.410650 --0.999196 0.000000 -0.040096 --0.999195 0.000005 -0.040118 --0.999195 0.000005 -0.040118 --0.911793 0.000000 -0.410650 --0.911793 0.000000 -0.410650 --0.000000 1.000000 0.000000 --0.000000 0.986432 -0.164171 --0.000000 0.987087 -0.160183 --0.000000 0.987087 -0.160183 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000000 --0.000000 0.987087 -0.160183 --0.000000 1.000000 0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --0.000001 0.998442 -0.055795 --0.000000 0.998442 -0.055795 --0.000000 0.999610 -0.027909 --0.000000 0.999610 -0.027909 -0.000000 0.999610 -0.027908 --0.000001 0.998442 -0.055795 -1.000000 0.000000 0.000000 -0.986171 0.000000 -0.165731 -0.987088 0.000000 -0.160182 -0.987088 0.000000 -0.160182 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.987088 0.000000 -0.160182 -1.000000 0.000000 0.000000 --0.000000 1.000000 -0.000000 -0.000000 1.000000 0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 --1.000000 0.000000 0.000001 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020064 --0.999799 0.000000 -0.020064 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000001 -0.000001 0.987087 0.160183 --0.000000 0.987088 0.160181 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 -0.000001 0.987087 0.160183 --0.000000 1.000000 0.000000 --0.000000 1.000000 -0.000000 -0.000001 -1.000000 -0.000000 -0.000001 -0.987087 0.160183 -0.000001 -0.987087 0.160183 -0.000001 -1.000000 -0.000000 -0.000001 -0.987087 0.160183 -0.000000 -1.000000 0.000000 -0.000001 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000001 -0.000001 -1.000000 -0.000000 -0.000000 -1.000000 0.000001 -0.000001 -1.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 -0.000000 --0.162115 0.000000 0.986772 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.162115 0.000000 0.986772 --0.162115 0.000000 0.986772 --0.160182 0.987087 0.000000 --0.155746 0.975487 0.155460 -0.000000 0.987396 0.158267 -0.000000 0.987396 0.158267 -0.000000 1.000000 0.000000 --0.160182 0.987087 0.000000 --0.987087 -0.000000 0.160183 --1.000000 0.000000 0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --0.987088 -0.000001 0.160181 --0.987087 -0.000000 0.160183 --1.000000 -0.000000 -0.000000 --0.987088 -0.000001 0.160181 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.987087 0.000000 0.160183 -1.000000 0.000000 0.000000 -0.987087 0.000000 0.160183 -0.987087 0.000000 0.160183 -1.000000 0.000000 0.000000 -0.987087 0.000000 0.160183 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 --0.987396 0.000000 0.158268 --0.987396 0.000000 0.158268 --0.709857 0.000000 0.704345 --0.709857 0.000000 0.704345 --0.709857 0.000000 0.704345 --0.987396 0.000000 0.158268 -0.000000 0.000000 1.000000 -0.000000 0.162115 0.986772 --0.018551 0.170483 0.985186 -0.000000 0.000000 1.000000 --0.018551 0.170483 0.985186 --0.173478 0.024209 0.984540 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.173478 0.024209 0.984540 -0.000000 0.000000 1.000000 --0.173478 0.024209 0.984540 --0.162115 0.000000 0.986772 --0.173478 0.024209 0.984540 --0.018551 0.170483 0.985186 --0.155928 0.141040 0.977647 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.162115 0.986772 -0.000000 0.162115 0.986772 -0.000000 0.162115 0.986772 -0.000000 0.000000 1.000000 --0.999195 -0.000000 -0.040117 --0.999195 0.000000 -0.040117 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999195 -0.000000 -0.040117 --0.999799 0.000000 -0.020062 --1.000000 0.000000 0.000001 --1.000000 -0.000000 0.000001 --1.000000 -0.000000 0.000001 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999195 0.000000 -0.040116 --0.999195 -0.000000 -0.040117 --0.985934 0.159934 -0.048521 --0.985934 0.159934 -0.048521 --0.985934 0.159934 -0.048521 --0.999195 0.000000 -0.040116 --0.974743 0.158179 0.157659 --0.987087 0.160182 0.000001 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987396 0.000000 0.158268 --0.974743 0.158179 0.157659 --1.000000 -0.000000 0.000001 --1.000000 -0.000000 0.000001 --0.999799 -0.000000 -0.020062 --0.999799 -0.000000 -0.020062 --0.999799 0.000000 -0.020062 --1.000000 -0.000000 0.000001 --0.999799 -0.000000 -0.020062 --0.999195 -0.000000 -0.040117 --0.999195 -0.000000 -0.040117 --0.999195 -0.000000 -0.040117 --0.999799 0.000000 -0.020062 --0.999799 -0.000000 -0.020062 --0.999195 0.000000 -0.040117 --0.999195 0.000000 -0.040116 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --0.999195 0.000000 -0.040117 --0.999799 0.000000 -0.020062 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000001 --0.999799 0.000000 -0.020062 --0.999799 0.000000 -0.020062 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000000 --0.999195 0.000000 -0.040116 --0.999195 0.000005 -0.040118 --0.999196 0.000000 -0.040096 --0.999196 0.000000 -0.040096 --0.999196 0.000000 -0.040095 --0.999195 0.000000 -0.040116 --1.000000 -0.000000 0.000001 --1.000000 0.000000 0.000000 --0.987087 0.160182 0.000001 --0.987087 0.160182 0.000001 --0.987087 0.160182 0.000000 --1.000000 -0.000000 0.000001 --0.987087 0.160182 0.000000 --0.987087 0.160182 0.000001 --0.707107 0.707107 0.000000 --0.707107 0.707107 0.000000 --0.707107 0.707107 0.000000 --0.987087 0.160182 0.000000 --0.707107 0.707107 0.000000 --0.707107 0.707107 0.000000 --0.160182 0.987087 0.000000 --0.160182 0.987087 0.000000 --0.160182 0.987087 0.000000 --0.707107 0.707107 0.000000 --0.160182 0.987087 0.000000 --0.160182 0.987087 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 --0.160182 0.987087 0.000000 --1.000000 -0.000000 0.000001 --0.987087 0.160182 0.000000 --0.986399 0.162556 -0.024328 --0.986399 0.162556 -0.024328 --0.999799 -0.000000 -0.020062 --1.000000 -0.000000 0.000001 --0.986399 0.162556 -0.024328 --0.987087 0.160182 0.000000 --0.707107 0.707107 0.000000 --0.707107 0.707107 0.000000 --0.705633 0.707781 -0.033588 --0.986399 0.162556 -0.024328 --0.705633 0.707781 -0.033588 --0.707107 0.707107 0.000000 --0.160182 0.987087 0.000000 --0.160182 0.987087 0.000000 --0.161626 0.986374 -0.030703 --0.705633 0.707781 -0.033588 -0.000000 0.999610 -0.027908 --0.000000 0.999610 -0.027909 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.999610 -0.027908 --0.000001 0.998442 -0.055795 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000001 0.998442 -0.055795 --0.000001 0.998442 -0.055795 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.999610 -0.027908 --0.161626 0.986374 -0.030703 --0.160182 0.987087 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 --0.000000 0.999610 -0.027909 --0.161626 0.986374 -0.030703 --0.159831 0.985228 -0.061474 --0.000000 0.998442 -0.055795 --0.000000 0.998442 -0.055794 --0.000000 0.998442 -0.055794 --0.159831 0.985228 -0.061474 --0.159831 0.985228 -0.061474 --0.000000 0.999610 -0.027909 --0.000000 0.998442 -0.055795 --0.159831 0.985228 -0.061474 --0.159831 0.985228 -0.061474 --0.161626 0.986374 -0.030703 --0.000000 0.999610 -0.027909 --0.161626 0.986374 -0.030703 --0.159831 0.985228 -0.061474 --0.705588 0.705376 -0.067746 --0.705588 0.705376 -0.067746 --0.705633 0.707781 -0.033588 --0.161626 0.986374 -0.030703 --0.705588 0.705376 -0.067746 --0.985934 0.159934 -0.048521 --0.986399 0.162556 -0.024328 --0.986399 0.162556 -0.024328 --0.705633 0.707781 -0.033588 --0.705588 0.705376 -0.067746 --0.999195 -0.000000 -0.040117 --0.999799 -0.000000 -0.020062 --0.986399 0.162556 -0.024328 --0.986399 0.162556 -0.024328 --0.985934 0.159934 -0.048521 --0.999195 -0.000000 -0.040117 --0.999195 0.000000 -0.040116 --0.985934 0.159934 -0.048521 --0.902713 0.144766 -0.405157 --0.902713 0.144766 -0.405157 --0.911793 0.000000 -0.410650 --0.999195 0.000000 -0.040116 --0.985934 0.159934 -0.048521 --0.705588 0.705377 -0.067746 --0.645117 0.643053 -0.412683 --0.645117 0.643053 -0.412683 --0.902713 0.144766 -0.405157 --0.985934 0.159934 -0.048521 --0.645117 0.643053 -0.412683 --0.705588 0.705377 -0.067746 --0.159831 0.985228 -0.061474 --0.159831 0.985228 -0.061474 --0.144762 0.898824 -0.413714 --0.645117 0.643053 -0.412683 --0.144762 0.898824 -0.413714 --0.159831 0.985228 -0.061474 --0.000000 0.998442 -0.055794 --0.000000 0.998442 -0.055794 -0.000000 0.906973 -0.421189 --0.144762 0.898824 -0.413714 --0.000000 0.998441 -0.055810 --0.000005 0.998442 -0.055795 --0.000001 0.999610 -0.027908 --0.000001 0.999610 -0.027908 -0.000000 0.999611 -0.027905 --0.000000 0.998441 -0.055810 -0.000000 0.987396 0.158267 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.987396 0.158267 -0.000000 0.987396 0.158267 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 --0.000001 0.999610 -0.027908 --0.000001 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000000 1.000000 0.000000 --0.000001 0.999610 -0.027908 --0.000005 0.998442 -0.055795 -0.000001 0.998442 -0.055795 -0.000001 0.998442 -0.055795 -0.000000 0.999610 -0.027908 --0.000001 0.999610 -0.027908 --0.000002 0.998442 -0.055798 --0.000005 0.998442 -0.055795 --0.000000 0.998441 -0.055810 --0.000000 0.998441 -0.055810 --0.000000 0.998441 -0.055815 --0.000002 0.998442 -0.055798 --0.000002 0.998442 -0.055798 --0.000000 0.998441 -0.055815 -0.000000 0.906973 -0.421189 -0.000000 0.906973 -0.421189 -0.000000 0.906973 -0.421189 --0.000002 0.998442 -0.055798 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.999611 -0.027905 -0.000000 0.999611 -0.027905 --0.000001 0.999610 -0.027908 -0.000000 1.000000 0.000000 --0.987396 0.000000 0.158268 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000001 --1.000000 0.000000 0.000001 --0.987396 0.000000 0.158268 --0.987396 0.000000 0.158268 --0.999195 0.000000 -0.040116 --0.999196 0.000000 -0.040095 --0.999799 0.000000 -0.020064 --0.999799 0.000000 -0.020064 --0.999799 0.000000 -0.020062 --0.999195 0.000000 -0.040116 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000001 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000001 --1.000000 -0.000000 -0.000001 --1.000000 -0.000000 -0.000001 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 0.000001 --1.000000 -0.000000 -0.000001 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 -0.000000 --1.000000 -0.000000 0.000000 --1.000000 -0.000000 -0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000001 --0.000000 1.000000 -0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000001 --0.000000 1.000000 -0.000001 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 0.000003 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000001 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000003 -0.000000 1.000000 0.000003 --0.000000 1.000000 0.000021 -0.000000 1.000000 0.000001 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.293668 0.950362 -0.102818 -0.437377 0.898427 0.039117 -0.466777 0.877351 -0.111237 -0.466777 0.877351 -0.111237 --0.378489 0.922436 0.076533 --0.293668 0.950362 -0.102818 --0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 --0.053947 0.933079 -0.355602 --0.053947 0.933079 -0.355602 -0.000000 0.928568 -0.371161 --0.000000 1.000000 0.000002 -0.083860 0.883048 -0.461729 --0.058021 0.917041 0.394549 --0.219047 0.944662 0.244197 --0.219047 0.944662 0.244197 -0.334821 0.862576 -0.379285 -0.083860 0.883048 -0.461729 -0.278630 0.944534 0.173843 --0.199706 0.956891 -0.210898 --0.126855 0.942566 -0.308993 --0.126855 0.942566 -0.308993 -0.204871 0.931518 0.300504 -0.278630 0.944534 0.173843 -0.437377 0.898427 0.039117 --0.293668 0.950362 -0.102818 --0.199706 0.956891 -0.210898 --0.199706 0.956891 -0.210898 -0.278630 0.944534 0.173843 -0.437377 0.898427 0.039117 -0.000000 0.902777 -0.430109 -0.000000 0.903393 0.428813 --0.058021 0.917041 0.394549 --0.058021 0.917041 0.394549 -0.083860 0.883048 -0.461729 -0.000000 0.902777 -0.430109 --0.219047 0.944662 0.244197 --0.378489 0.922436 0.076533 -0.466777 0.877351 -0.111237 -0.466777 0.877351 -0.111237 -0.334821 0.862576 -0.379285 --0.219047 0.944662 0.244197 -0.204871 0.931518 0.300504 --0.126855 0.942566 -0.308993 --0.053947 0.933079 -0.355602 --0.053947 0.933079 -0.355602 -0.000000 1.000000 0.000002 -0.204871 0.931518 0.300504 --0.984855 0.000001 0.173381 --0.973923 0.000000 -0.226877 --0.906193 0.386266 -0.172083 --0.906193 0.386266 -0.172083 --0.924386 0.345298 0.162109 --0.984855 0.000001 0.173381 -0.965948 0.000000 0.258737 -0.972507 0.000000 -0.232875 -0.922754 0.317517 -0.218422 -0.922754 0.317517 -0.218422 -0.876796 0.404449 0.260095 -0.965948 0.000000 0.258737 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.000000 1.000000 --0.165253 0.000000 -0.986251 -0.000000 0.000000 -1.000000 -0.000000 0.389580 -0.920992 -0.000000 0.389580 -0.920992 --0.145080 0.399992 -0.904963 --0.165253 0.000000 -0.986251 -0.661497 0.000000 -0.749948 -0.174458 0.000000 -0.984665 -0.161326 0.320071 -0.933557 -0.161326 0.320071 -0.933557 -0.628452 0.312262 -0.712418 -0.661497 0.000000 -0.749948 --0.139943 0.000000 0.990160 --0.682762 0.000000 0.730641 --0.629331 0.383170 0.676109 --0.629331 0.383170 0.676109 --0.134000 0.341445 0.930301 --0.139943 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.000000 1.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 -0.865983 0.000000 -0.500074 -0.472043 0.840449 -0.266122 -0.472043 0.840449 -0.266122 --0.000001 0.480135 -0.877194 -0.000000 0.000000 -1.000000 --0.973923 0.000000 -0.226877 --0.766123 0.000000 -0.642694 --0.686198 0.460064 -0.563448 --0.686198 0.460064 -0.563448 --0.906193 0.386266 -0.172083 --0.973923 0.000000 -0.226877 -0.865983 0.000000 -0.500074 -0.965948 0.000000 0.258737 -0.876796 0.404449 0.260095 -0.876796 0.404449 0.260095 -0.472043 0.840449 -0.266122 -0.865983 0.000000 -0.500074 -0.000000 0.000000 1.000000 --0.139943 0.000000 0.990160 --0.134000 0.341445 0.930301 --0.134000 0.341445 0.930301 -0.000000 0.335574 0.942014 -0.000000 0.000000 1.000000 -0.174458 0.000000 -0.984665 -0.000000 0.000000 -1.000000 --0.000000 0.335181 -0.942154 --0.000000 0.335181 -0.942154 -0.161326 0.320071 -0.933557 -0.174458 0.000000 -0.984665 -0.972507 0.000000 -0.232875 -0.661497 0.000000 -0.749948 -0.628452 0.312262 -0.712418 -0.628452 0.312262 -0.712418 -0.922754 0.317517 -0.218422 -0.972507 0.000000 -0.232875 --0.682762 0.000000 0.730641 --0.984855 0.000001 0.173381 --0.924386 0.345298 0.162109 --0.924386 0.345298 0.162109 --0.629331 0.383170 0.676109 --0.682762 0.000000 0.730641 --0.446771 0.000000 -0.894648 --0.165253 0.000000 -0.986251 --0.145080 0.399992 -0.904963 --0.145080 0.399992 -0.904963 --0.391985 0.437360 -0.809360 --0.446771 0.000000 -0.894648 --0.766123 0.000000 -0.642694 --0.446771 0.000000 -0.894648 --0.391985 0.437360 -0.809360 --0.391985 0.437360 -0.809360 --0.686198 0.460064 -0.563448 --0.766123 0.000000 -0.642694 -0.437377 0.898427 0.039117 -0.876796 0.404449 0.260095 -0.922754 0.317517 -0.218422 -0.922754 0.317517 -0.218422 -0.466777 0.877351 -0.111237 -0.437377 0.898427 0.039117 --0.378489 0.922436 0.076533 --0.924386 0.345298 0.162109 --0.906193 0.386266 -0.172083 --0.906193 0.386266 -0.172083 --0.293668 0.950362 -0.102818 --0.378489 0.922436 0.076533 -0.000000 0.960502 0.278273 -0.016761 0.961573 0.274037 -0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 --0.000000 1.000000 0.000002 -0.000000 0.960502 0.278273 --0.145080 0.399992 -0.904963 -0.000000 0.389580 -0.920992 -0.000000 0.928568 -0.371161 -0.000000 0.928568 -0.371161 --0.053947 0.933079 -0.355602 --0.145080 0.399992 -0.904963 --0.058021 0.917041 0.394549 --0.134000 0.341445 0.930301 --0.629331 0.383170 0.676109 --0.629331 0.383170 0.676109 --0.219047 0.944662 0.244197 --0.058021 0.917041 0.394549 -0.334821 0.862576 -0.379285 -0.628452 0.312262 -0.712418 -0.161326 0.320071 -0.933557 -0.161326 0.320071 -0.933557 -0.083860 0.883048 -0.461729 -0.334821 0.862576 -0.379285 --0.199706 0.956891 -0.210898 --0.686198 0.460064 -0.563448 --0.391985 0.437360 -0.809360 --0.391985 0.437360 -0.809360 --0.126855 0.942566 -0.308993 --0.199706 0.956891 -0.210898 --0.293668 0.950362 -0.102818 --0.906193 0.386266 -0.172083 --0.686198 0.460064 -0.563448 --0.686198 0.460064 -0.563448 --0.199706 0.956891 -0.210898 --0.293668 0.950362 -0.102818 -0.278630 0.944534 0.173843 -0.472043 0.840449 -0.266122 -0.876796 0.404449 0.260095 -0.876796 0.404449 0.260095 -0.437377 0.898427 0.039117 -0.278630 0.944534 0.173843 -0.000000 0.903393 0.428813 -0.000000 0.335574 0.942014 --0.134000 0.341445 0.930301 --0.134000 0.341445 0.930301 --0.058021 0.917041 0.394549 -0.000000 0.903393 0.428813 -0.161326 0.320071 -0.933557 --0.000000 0.335181 -0.942154 -0.000000 0.902777 -0.430109 -0.000000 0.902777 -0.430109 -0.083860 0.883048 -0.461729 -0.161326 0.320071 -0.933557 --0.629331 0.383170 0.676109 --0.924386 0.345298 0.162109 --0.378489 0.922436 0.076533 --0.378489 0.922436 0.076533 --0.219047 0.944662 0.244197 --0.629331 0.383170 0.676109 -0.922754 0.317517 -0.218422 -0.628452 0.312262 -0.712418 -0.334821 0.862576 -0.379285 -0.334821 0.862576 -0.379285 -0.466777 0.877351 -0.111237 -0.922754 0.317517 -0.218422 --0.126855 0.942566 -0.308993 --0.391985 0.437360 -0.809360 --0.145080 0.399992 -0.904963 --0.145080 0.399992 -0.904963 --0.053947 0.933079 -0.355602 --0.126855 0.942566 -0.308993 -0.204871 0.931518 0.300504 -0.016761 0.961573 0.274037 -0.472043 0.840449 -0.266122 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.016761 0.961573 0.274037 -0.016761 0.961573 0.274037 -0.000000 0.960502 0.278273 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.999997 -0.002593 -0.000000 0.999997 -0.002593 -0.016761 0.961573 0.274037 -0.000000 0.482408 0.875946 -0.016761 0.961573 0.274037 -0.204871 0.931518 0.300504 -0.000000 1.000000 0.000002 -0.204871 0.931518 0.300504 -0.472043 0.840449 -0.266122 -0.278630 0.944534 0.173843 --0.000001 0.480135 -0.877194 -0.472043 0.840449 -0.266122 -0.016761 0.961573 0.274037 -0.016761 0.961573 0.274037 -0.000000 0.999997 -0.002593 --0.000001 0.480135 -0.877194 -0.293668 0.950362 -0.102818 -0.378489 0.922436 0.076533 --0.466777 0.877352 -0.111236 --0.466777 0.877352 -0.111236 --0.437377 0.898427 0.039117 -0.293668 0.950362 -0.102818 --0.000000 1.000000 0.000002 -0.000000 0.928568 -0.371161 -0.053947 0.933079 -0.355603 -0.053947 0.933079 -0.355603 -0.000000 1.000000 0.000002 --0.000000 1.000000 0.000002 --0.083860 0.883048 -0.461729 --0.334821 0.862576 -0.379285 -0.219047 0.944662 0.244196 -0.219047 0.944662 0.244196 -0.058021 0.917041 0.394549 --0.083860 0.883048 -0.461729 --0.278630 0.944534 0.173843 --0.204871 0.931518 0.300504 -0.126855 0.942566 -0.308993 -0.126855 0.942566 -0.308993 -0.199706 0.956891 -0.210898 --0.278630 0.944534 0.173843 --0.437377 0.898427 0.039117 --0.278630 0.944534 0.173843 -0.199706 0.956891 -0.210898 -0.199706 0.956891 -0.210898 -0.293668 0.950362 -0.102818 --0.437377 0.898427 0.039117 -0.000000 0.902777 -0.430109 --0.083860 0.883048 -0.461729 -0.058021 0.917041 0.394549 -0.058021 0.917041 0.394549 -0.000000 0.903393 0.428813 -0.000000 0.902777 -0.430109 -0.219047 0.944662 0.244196 --0.334821 0.862576 -0.379285 --0.466777 0.877352 -0.111236 --0.466777 0.877352 -0.111236 -0.378489 0.922436 0.076533 -0.219047 0.944662 0.244196 --0.204871 0.931518 0.300504 -0.000000 1.000000 0.000002 -0.053947 0.933079 -0.355603 -0.053947 0.933079 -0.355603 -0.126855 0.942566 -0.308993 --0.204871 0.931518 0.300504 -0.984855 0.000001 0.173382 -0.924386 0.345297 0.162111 -0.906193 0.386266 -0.172082 -0.906193 0.386266 -0.172082 -0.973923 0.000000 -0.226877 -0.984855 0.000001 0.173382 --0.965948 0.000000 0.258737 --0.876796 0.404449 0.260094 --0.922754 0.317518 -0.218422 --0.922754 0.317518 -0.218422 --0.972507 0.000000 -0.232875 --0.965948 0.000000 0.258737 -0.000000 0.000000 1.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.165253 0.000000 -0.986251 -0.145080 0.399992 -0.904963 -0.000000 0.389580 -0.920992 -0.000000 0.389580 -0.920992 -0.000000 0.000000 -1.000000 -0.165253 0.000000 -0.986251 --0.661497 0.000000 -0.749948 --0.628452 0.312262 -0.712418 --0.161326 0.320071 -0.933557 --0.161326 0.320071 -0.933557 --0.174458 0.000000 -0.984665 --0.661497 0.000000 -0.749948 -0.139943 0.000000 0.990160 -0.134000 0.341445 0.930301 -0.629330 0.383170 0.676110 -0.629330 0.383170 0.676110 -0.682761 0.000001 0.730642 -0.139943 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 -0.000001 0.480135 -0.877194 --0.472044 0.840449 -0.266122 --0.472044 0.840449 -0.266122 --0.865983 0.000000 -0.500074 -0.000000 0.000000 -1.000000 -0.973923 0.000000 -0.226877 -0.906193 0.386266 -0.172082 -0.686198 0.460063 -0.563448 -0.686198 0.460063 -0.563448 -0.766123 0.000000 -0.642694 -0.973923 0.000000 -0.226877 --0.865983 0.000000 -0.500074 --0.472044 0.840449 -0.266122 --0.876796 0.404449 0.260094 --0.876796 0.404449 0.260094 --0.965948 0.000000 0.258737 --0.865983 0.000000 -0.500074 -0.000000 0.000000 1.000000 -0.000000 0.335574 0.942014 -0.134000 0.341445 0.930301 -0.134000 0.341445 0.930301 -0.139943 0.000000 0.990160 -0.000000 0.000000 1.000000 --0.174458 0.000000 -0.984665 --0.161326 0.320071 -0.933557 --0.000000 0.335181 -0.942154 --0.000000 0.335181 -0.942154 -0.000000 0.000000 -1.000000 --0.174458 0.000000 -0.984665 --0.972507 0.000000 -0.232875 --0.922754 0.317518 -0.218422 --0.628452 0.312262 -0.712418 --0.628452 0.312262 -0.712418 --0.661497 0.000000 -0.749948 --0.972507 0.000000 -0.232875 -0.682761 0.000001 0.730642 -0.629330 0.383170 0.676110 -0.924386 0.345297 0.162111 -0.924386 0.345297 0.162111 -0.984855 0.000001 0.173382 -0.682761 0.000001 0.730642 -0.446771 0.000000 -0.894648 -0.391985 0.437360 -0.809360 -0.145080 0.399992 -0.904963 -0.145080 0.399992 -0.904963 -0.165253 0.000000 -0.986251 -0.446771 0.000000 -0.894648 -0.766123 0.000000 -0.642694 -0.686198 0.460063 -0.563448 -0.391985 0.437360 -0.809360 -0.391985 0.437360 -0.809360 -0.446771 0.000000 -0.894648 -0.766123 0.000000 -0.642694 --0.437377 0.898427 0.039117 --0.466777 0.877352 -0.111236 --0.922754 0.317518 -0.218422 --0.922754 0.317518 -0.218422 --0.876796 0.404449 0.260094 --0.437377 0.898427 0.039117 -0.378489 0.922436 0.076533 -0.293668 0.950362 -0.102818 -0.906193 0.386266 -0.172082 -0.906193 0.386266 -0.172082 -0.924386 0.345297 0.162111 -0.378489 0.922436 0.076533 -0.000000 0.960502 0.278273 --0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 --0.016761 0.961573 0.274037 -0.000000 0.960502 0.278273 -0.145080 0.399992 -0.904963 -0.053947 0.933079 -0.355603 -0.000000 0.928568 -0.371161 -0.000000 0.928568 -0.371161 -0.000000 0.389580 -0.920992 -0.145080 0.399992 -0.904963 -0.058021 0.917041 0.394549 -0.219047 0.944662 0.244196 -0.629330 0.383170 0.676110 -0.629330 0.383170 0.676110 -0.134000 0.341445 0.930301 -0.058021 0.917041 0.394549 --0.334821 0.862576 -0.379285 --0.083860 0.883048 -0.461729 --0.161326 0.320071 -0.933557 --0.161326 0.320071 -0.933557 --0.628452 0.312262 -0.712418 --0.334821 0.862576 -0.379285 -0.199706 0.956891 -0.210898 -0.126855 0.942566 -0.308993 -0.391985 0.437360 -0.809360 -0.391985 0.437360 -0.809360 -0.686198 0.460063 -0.563448 -0.199706 0.956891 -0.210898 -0.293668 0.950362 -0.102818 -0.199706 0.956891 -0.210898 -0.686198 0.460063 -0.563448 -0.686198 0.460063 -0.563448 -0.906193 0.386266 -0.172082 -0.293668 0.950362 -0.102818 --0.278630 0.944534 0.173843 --0.437377 0.898427 0.039117 --0.876796 0.404449 0.260094 --0.876796 0.404449 0.260094 --0.472044 0.840449 -0.266122 --0.278630 0.944534 0.173843 -0.000000 0.903393 0.428813 -0.058021 0.917041 0.394549 -0.134000 0.341445 0.930301 -0.134000 0.341445 0.930301 -0.000000 0.335574 0.942014 -0.000000 0.903393 0.428813 --0.161326 0.320071 -0.933557 --0.083860 0.883048 -0.461729 -0.000000 0.902777 -0.430109 -0.000000 0.902777 -0.430109 --0.000000 0.335181 -0.942154 --0.161326 0.320071 -0.933557 -0.629330 0.383170 0.676110 -0.219047 0.944662 0.244196 -0.378489 0.922436 0.076533 -0.378489 0.922436 0.076533 -0.924386 0.345297 0.162111 -0.629330 0.383170 0.676110 --0.922754 0.317518 -0.218422 --0.466777 0.877352 -0.111236 --0.334821 0.862576 -0.379285 --0.334821 0.862576 -0.379285 --0.628452 0.312262 -0.712418 --0.922754 0.317518 -0.218422 -0.126855 0.942566 -0.308993 -0.053947 0.933079 -0.355603 -0.145080 0.399992 -0.904963 -0.145080 0.399992 -0.904963 -0.391985 0.437360 -0.809360 -0.126855 0.942566 -0.308993 --0.204871 0.931518 0.300504 --0.472044 0.840449 -0.266122 --0.016761 0.961573 0.274037 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 0.482408 0.875946 -0.000000 0.960502 0.278273 --0.016761 0.961573 0.274037 --0.016761 0.961573 0.274037 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 --0.016761 0.961573 0.274037 -0.000000 0.999997 -0.002593 -0.000000 0.999997 -0.002593 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 --0.016761 0.961573 0.274037 -0.000000 1.000000 0.000002 --0.204871 0.931518 0.300504 --0.204871 0.931518 0.300504 --0.278630 0.944534 0.173843 --0.472044 0.840449 -0.266122 -0.000001 0.480135 -0.877194 -0.000000 0.999997 -0.002593 --0.016761 0.961573 0.274037 --0.016761 0.961573 0.274037 --0.472044 0.840449 -0.266122 -0.000001 0.480135 -0.877194 -0.159831 0.985228 -0.061474 -0.705588 0.705376 -0.067746 -0.705588 0.705377 -0.067746 -0.705588 0.705377 -0.067746 -0.159831 0.985228 -0.061474 -0.159831 0.985228 -0.061474 -0.987087 0.160182 0.000001 -0.707107 0.707107 0.000000 -0.700074 0.696893 0.155682 -0.700074 0.696893 0.155682 -0.974743 0.158179 0.157659 -0.987087 0.160182 0.000001 -0.705588 0.705377 -0.067746 -0.705588 0.705376 -0.067746 -0.985934 0.159933 -0.048522 -0.985934 0.159933 -0.048522 -0.985935 0.159933 -0.048523 -0.705588 0.705377 -0.067746 -0.707107 0.707107 0.000000 -0.160182 0.987087 0.000000 -0.155746 0.975487 0.155460 -0.155746 0.975487 0.155460 -0.700074 0.696893 0.155682 -0.707107 0.707107 0.000000 -0.155927 0.141040 0.977647 -0.541661 0.532698 0.650258 -0.107470 0.721820 0.683686 -0.107470 0.721820 0.683686 -0.018551 0.170483 0.985186 -0.155927 0.141040 0.977647 -0.173478 0.024209 0.984540 -0.720099 0.114166 0.684415 -0.541661 0.532698 0.650258 -0.541661 0.532698 0.650258 -0.155927 0.141040 0.977647 -0.173478 0.024209 0.984540 -0.541661 0.532698 0.650258 -0.700074 0.696893 0.155682 -0.155746 0.975487 0.155460 -0.155746 0.975487 0.155460 -0.107470 0.721820 0.683686 -0.541661 0.532698 0.650258 -0.720099 0.114166 0.684415 -0.974743 0.158179 0.157659 -0.700074 0.696893 0.155682 -0.700074 0.696893 0.155682 -0.541661 0.532698 0.650258 -0.720099 0.114166 0.684415 -0.902713 0.144766 -0.405157 -0.676471 0.107126 -0.728637 -0.456612 0.453865 -0.765188 -0.456612 0.453865 -0.765188 -0.645117 0.643053 -0.412683 -0.902713 0.144766 -0.405157 -0.456612 0.453865 -0.765188 -0.107386 0.671902 -0.732814 -0.144762 0.898824 -0.413714 -0.144762 0.898824 -0.413714 -0.645117 0.643053 -0.412683 -0.456612 0.453865 -0.765188 -0.676471 0.107126 -0.728637 -0.902713 0.144766 -0.405157 -0.911793 0.000000 -0.410650 -0.911793 0.000000 -0.410650 -0.692241 0.000000 -0.721666 -0.676471 0.107126 -0.728637 -0.911793 0.000000 -0.410650 -0.692242 0.000000 -0.721666 -0.692241 0.000000 -0.721666 -0.692241 0.000000 -0.721666 -0.911793 0.000000 -0.410650 -0.911793 0.000000 -0.410650 -0.000000 -0.987087 -0.160182 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.987087 -0.160182 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -0.987087 -0.160182 -0.000000 -1.000000 0.000000 -0.000000 -0.986432 -0.164170 -0.000000 -0.986432 -0.164170 -0.000000 -0.701325 -0.712842 -0.000000 -0.707108 -0.707105 -0.000000 -0.707108 -0.707105 -0.000000 -0.987087 -0.160182 -0.000000 -0.986432 -0.164170 -0.000000 -0.701325 -0.712842 -0.000000 -0.159534 -0.987193 -0.000000 -0.160184 -0.987087 -0.000000 -0.160184 -0.987087 -0.000000 -0.707108 -0.707105 -0.000000 -0.701325 -0.712842 -0.000000 -0.159534 -0.987193 -0.000000 0.159534 -0.987192 -0.000000 0.160184 -0.987087 -0.000000 0.160184 -0.987087 -0.000000 -0.160184 -0.987087 -0.000000 -0.159534 -0.987193 -0.000000 0.160184 -0.987087 -0.000000 0.159534 -0.987192 -0.000000 0.701324 -0.712843 -0.000000 0.701324 -0.712843 -0.000000 0.707107 -0.707106 -0.000000 0.160184 -0.987087 -0.000000 0.707107 -0.707106 -0.000000 0.701324 -0.712843 -0.000000 0.986432 -0.164171 -0.000000 0.986432 -0.164171 -0.000000 0.987087 -0.160183 -0.000000 0.707107 -0.707106 -0.000000 0.686823 -0.726825 -0.000000 0.686823 -0.726825 -0.000000 0.906973 -0.421189 -0.000000 0.906973 -0.421189 -0.000000 0.906973 -0.421189 -0.000000 0.686823 -0.726825 -0.000000 0.906973 -0.421189 -0.144762 0.898824 -0.413714 -0.107386 0.671902 -0.732814 -0.107386 0.671902 -0.732814 -0.000000 0.686823 -0.726825 -0.000000 0.906973 -0.421189 --0.160183 0.000000 -0.987087 --0.159277 0.000000 -0.987234 --0.699024 0.000000 -0.715098 --0.699024 0.000000 -0.715098 --0.707108 0.000000 -0.707105 --0.160183 0.000000 -0.987087 --0.707108 0.000000 -0.707105 --0.699024 0.000000 -0.715098 --0.986171 0.000000 -0.165730 --0.986171 0.000000 -0.165730 --0.987088 0.000000 -0.160181 --0.707108 0.000000 -0.707105 -0.987088 -0.000000 -0.160181 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -0.987088 -0.000000 -0.160181 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -0.987088 -0.000000 -0.160181 -1.000000 -0.000000 0.000000 -0.986171 -0.000000 -0.165731 -0.986171 -0.000000 -0.165731 -0.699024 -0.000000 -0.715098 -0.707109 -0.000000 -0.707105 -0.707109 -0.000000 -0.707105 -0.987088 -0.000000 -0.160181 -0.986171 -0.000000 -0.165731 -0.699024 -0.000000 -0.715098 -0.159277 -0.000000 -0.987234 -0.160184 -0.000000 -0.987087 -0.160184 -0.000000 -0.987087 -0.707109 -0.000000 -0.707105 -0.699024 -0.000000 -0.715098 -0.159277 -0.000000 -0.987234 --0.159277 0.000000 -0.987234 --0.160183 0.000000 -0.987087 --0.160183 0.000000 -0.987087 -0.160184 -0.000000 -0.987087 -0.159277 -0.000000 -0.987234 -0.987396 0.000000 0.158268 -0.974743 0.158179 0.157659 -0.720099 0.114166 0.684415 -0.720099 0.114166 0.684415 -0.709858 0.000000 0.704345 -0.987396 0.000000 0.158268 -0.709858 0.000000 0.704345 -0.720099 0.114166 0.684415 -0.173478 0.024209 0.984540 -0.173478 0.024209 0.984540 -0.162115 0.000000 0.986772 -0.709858 0.000000 0.704345 -0.162115 -0.000000 0.986772 -0.162115 0.000000 0.986772 -0.709857 0.000000 0.704345 -0.709857 0.000000 0.704345 -0.709858 0.000000 0.704345 -0.162115 -0.000000 0.986772 --0.000000 0.707107 0.707106 --0.000001 0.987087 0.160183 -0.000000 0.987088 0.160181 -0.000000 0.987088 0.160181 -0.000000 0.707109 0.707105 --0.000000 0.707107 0.707106 -0.000000 0.160184 0.987087 -0.000000 0.160183 0.987087 --0.000000 0.707107 0.707106 --0.000000 0.707107 0.707106 -0.000000 0.707109 0.707105 -0.000000 0.160184 0.987087 --0.000000 -0.160183 0.987087 --0.000000 -0.160183 0.987087 -0.000000 0.160183 0.987087 -0.000000 0.160183 0.987087 -0.000000 0.160184 0.987087 --0.000000 -0.160183 0.987087 --0.000000 -0.707107 0.707106 --0.000000 -0.707107 0.707106 --0.000000 -0.160183 0.987087 --0.000000 -0.160183 0.987087 --0.000000 -0.160183 0.987087 --0.000000 -0.707107 0.707106 --0.000001 -0.987087 0.160183 --0.000001 -0.987087 0.160183 --0.000000 -0.707107 0.707106 --0.000000 -0.707107 0.707106 --0.000000 -0.707107 0.707106 --0.000001 -0.987087 0.160183 -0.000000 0.987396 0.158267 -0.000000 0.709859 0.704344 -0.000000 0.709859 0.704344 -0.000000 0.709859 0.704344 -0.000000 0.987396 0.158267 -0.000000 0.987396 0.158267 -0.000000 0.709859 0.704344 -0.000000 0.162115 0.986772 -0.000000 0.162115 0.986772 -0.000000 0.162115 0.986772 -0.000000 0.709859 0.704344 -0.000000 0.709859 0.704344 -0.000000 0.987396 0.158267 -0.000000 0.709858 0.704344 -0.107470 0.721820 0.683686 -0.107470 0.721820 0.683686 -0.155746 0.975487 0.155460 -0.000000 0.987396 0.158267 -0.018551 0.170483 0.985186 -0.107470 0.721820 0.683686 -0.000000 0.709858 0.704344 -0.000000 0.709858 0.704344 -0.000000 0.162115 0.986772 -0.018551 0.170483 0.985186 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.707107 0.000000 0.707106 --0.707107 0.000000 0.707106 --0.707107 0.000000 0.707106 --0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 --0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.707108 -0.000001 0.707105 -0.707108 0.000000 0.707106 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.160184 0.000000 0.987087 -0.707108 -0.000001 0.707105 -0.987087 -0.000000 0.160183 -0.707108 0.000000 0.707106 -0.707108 -0.000001 0.707105 -0.707108 -0.000001 0.707105 -0.987088 -0.000001 0.160180 -0.987087 -0.000000 0.160183 --0.707107 0.000000 0.707106 --0.707107 0.000000 0.707106 --0.987087 0.000000 0.160183 --0.987087 0.000000 0.160183 --0.987087 0.000000 0.160183 --0.707107 0.000000 0.707106 -0.911793 0.000000 -0.410650 -0.911793 0.000000 -0.410650 -0.999195 0.000005 -0.040120 -0.999195 0.000005 -0.040120 -0.999196 -0.000000 -0.040096 -0.911793 0.000000 -0.410650 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.987087 -0.160183 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.987087 -0.160183 -0.000000 1.000000 0.000000 -0.000000 0.987087 -0.160183 -0.000000 0.986432 -0.164171 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -0.000001 0.998442 -0.055795 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000000 0.998442 -0.055795 -0.000001 0.998442 -0.055795 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987088 0.000000 -0.160181 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987088 0.000000 -0.160181 --1.000000 0.000000 0.000000 --0.987088 0.000000 -0.160181 --0.986171 0.000000 -0.165730 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 -0.000000 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000000 -0.999799 0.000000 -0.020063 -0.999799 0.000000 -0.020063 -0.999799 0.000000 -0.020062 -1.000000 0.000000 0.000001 -0.000000 1.000000 -0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 0.000000 --0.000001 0.987087 0.160183 -0.000000 1.000000 -0.000000 -0.000000 1.000000 0.000000 --0.000001 0.987087 0.160183 -0.000000 1.000000 0.000000 -0.000000 0.987088 0.160181 --0.000001 -1.000000 -0.000000 --0.000001 -1.000000 -0.000000 --0.000000 -1.000000 0.000001 --0.000001 -1.000000 -0.000000 --0.000000 -1.000000 0.000001 --0.000000 -1.000000 0.000000 --0.000001 -1.000000 -0.000000 --0.000000 -1.000000 0.000000 --0.000001 -0.987087 0.160183 --0.000001 -1.000000 -0.000000 --0.000001 -0.987087 0.160183 --0.000001 -0.987087 0.160183 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 -0.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.160182 0.987087 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.987396 0.158267 -0.000000 0.987396 0.158267 -0.155746 0.975487 0.155460 -0.160182 0.987087 0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000001 -0.000000 -1.000000 -0.000000 -0.000000 -0.987088 -0.000001 0.160180 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -0.987087 -0.000000 0.160183 -0.987088 -0.000001 0.160180 -1.000000 -0.000000 -0.000000 -0.987087 -0.000000 0.160183 -1.000000 -0.000000 -0.000000 -1.000000 0.000000 0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987087 0.000000 0.160183 --1.000000 0.000000 0.000000 --0.987087 0.000000 0.160183 --0.987087 0.000000 0.160183 --1.000000 0.000000 0.000000 --0.987087 0.000000 0.160183 --1.000000 0.000000 0.000000 -0.987396 0.000000 0.158268 -0.709858 0.000000 0.704345 -0.709857 0.000000 0.704345 -0.709857 0.000000 0.704345 -0.987396 0.000000 0.158268 -0.987396 0.000000 0.158268 -0.000000 0.000000 1.000000 -0.162115 0.000000 0.986772 -0.173478 0.024209 0.984540 -0.018551 0.170483 0.985186 -0.000000 0.162115 0.986772 -0.000000 0.000000 1.000000 -0.173478 0.024209 0.984540 -0.018551 0.170483 0.985186 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.173478 0.024209 0.984540 -0.000000 0.000000 1.000000 -0.173478 0.024209 0.984540 -0.155927 0.141040 0.977647 -0.018551 0.170483 0.985186 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.162115 0.986772 -0.000000 0.162115 0.986772 -0.000000 0.162115 0.986772 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.999195 -0.000000 -0.040116 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999195 0.000000 -0.040116 -0.999195 -0.000000 -0.040116 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -1.000000 -0.000000 0.000001 -1.000000 -0.000000 0.000001 -1.000000 0.000000 0.000001 -0.999799 0.000000 -0.020062 -0.999195 0.000000 -0.040118 -0.985935 0.159933 -0.048523 -0.985934 0.159933 -0.048522 -0.985934 0.159933 -0.048522 -0.999195 -0.000000 -0.040117 -0.999195 0.000000 -0.040118 -0.974743 0.158179 0.157659 -0.987396 0.000000 0.158268 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.987087 0.160182 0.000001 -0.974743 0.158179 0.157659 -1.000000 -0.000000 0.000001 -0.999799 0.000000 -0.020062 -0.999799 -0.000000 -0.020062 -0.999799 -0.000000 -0.020062 -1.000000 -0.000000 0.000001 -1.000000 -0.000000 0.000001 -0.999799 -0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999195 -0.000000 -0.040116 -0.999195 -0.000000 -0.040116 -0.999195 -0.000000 -0.040117 -0.999799 -0.000000 -0.020062 -0.999195 0.000000 -0.040116 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -0.999195 0.000001 -0.040116 -0.999195 0.000000 -0.040116 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020062 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000001 -0.999799 0.000000 -0.020062 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000000 -0.999195 0.000001 -0.040116 -0.999196 -0.000000 -0.040095 -0.999196 -0.000000 -0.040096 -0.999196 -0.000000 -0.040096 -0.999195 0.000005 -0.040120 -0.999195 0.000001 -0.040116 -1.000000 -0.000000 0.000001 -0.987087 0.160182 0.000000 -0.987087 0.160182 0.000001 -0.987087 0.160182 0.000001 -1.000000 0.000000 0.000000 -1.000000 -0.000000 0.000001 -0.987087 0.160182 0.000000 -0.707107 0.707107 0.000001 -0.707107 0.707107 0.000000 -0.707107 0.707107 0.000000 -0.987087 0.160182 0.000001 -0.987087 0.160182 0.000000 -0.707107 0.707107 0.000001 -0.160183 0.987087 0.000000 -0.160182 0.987087 0.000000 -0.160182 0.987087 0.000000 -0.707107 0.707107 0.000000 -0.707107 0.707107 0.000001 -0.160183 0.987087 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.160182 0.987087 0.000000 -0.160183 0.987087 0.000000 -1.000000 -0.000000 0.000001 -0.999799 -0.000000 -0.020062 -0.986399 0.162556 -0.024328 -0.986399 0.162556 -0.024328 -0.987087 0.160182 0.000000 -1.000000 -0.000000 0.000001 -0.986399 0.162556 -0.024328 -0.705633 0.707781 -0.033587 -0.707107 0.707107 0.000001 -0.707107 0.707107 0.000001 -0.987087 0.160182 0.000000 -0.986399 0.162556 -0.024328 -0.705633 0.707781 -0.033587 -0.161626 0.986374 -0.030703 -0.160183 0.987087 0.000000 -0.160183 0.987087 0.000000 -0.707107 0.707107 0.000001 -0.705633 0.707781 -0.033587 -0.000000 0.999610 -0.027908 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000001 0.998442 -0.055795 --0.000001 0.998442 -0.055795 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.000001 0.998442 -0.055795 -0.000000 0.999610 -0.027908 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.999610 -0.027908 -0.000000 0.999610 -0.027908 -0.161626 0.986374 -0.030703 -0.000000 0.999610 -0.027908 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.160183 0.987087 0.000000 -0.161626 0.986374 -0.030703 -0.159831 0.985228 -0.061474 -0.159831 0.985228 -0.061474 -0.000000 0.998442 -0.055794 -0.000000 0.998442 -0.055794 -0.000000 0.998442 -0.055795 -0.159831 0.985228 -0.061474 -0.000000 0.999610 -0.027908 -0.161626 0.986374 -0.030703 -0.159831 0.985228 -0.061474 -0.159831 0.985228 -0.061474 -0.000000 0.998442 -0.055795 -0.000000 0.999610 -0.027908 -0.161626 0.986374 -0.030703 -0.705633 0.707781 -0.033587 -0.705588 0.705376 -0.067746 -0.705588 0.705376 -0.067746 -0.159831 0.985228 -0.061474 -0.161626 0.986374 -0.030703 -0.705588 0.705376 -0.067746 -0.705633 0.707781 -0.033587 -0.986399 0.162556 -0.024328 -0.986399 0.162556 -0.024328 -0.985934 0.159933 -0.048522 -0.705588 0.705376 -0.067746 -0.999195 -0.000000 -0.040117 -0.985934 0.159933 -0.048522 -0.986399 0.162556 -0.024328 -0.986399 0.162556 -0.024328 -0.999799 -0.000000 -0.020062 -0.999195 -0.000000 -0.040117 -0.999195 0.000000 -0.040118 -0.911793 0.000000 -0.410650 -0.902713 0.144766 -0.405157 -0.902713 0.144766 -0.405157 -0.985935 0.159933 -0.048523 -0.999195 0.000000 -0.040118 -0.985935 0.159933 -0.048523 -0.902713 0.144766 -0.405157 -0.645117 0.643053 -0.412683 -0.645117 0.643053 -0.412683 -0.705588 0.705377 -0.067746 -0.985935 0.159933 -0.048523 -0.645117 0.643053 -0.412683 -0.144762 0.898824 -0.413714 -0.159831 0.985228 -0.061474 -0.159831 0.985228 -0.061474 -0.705588 0.705377 -0.067746 -0.645117 0.643053 -0.412683 -0.144762 0.898824 -0.413714 -0.000000 0.906973 -0.421189 -0.000000 0.998442 -0.055794 -0.000000 0.998442 -0.055794 -0.159831 0.985228 -0.061474 -0.144762 0.898824 -0.413714 --0.000000 0.998441 -0.055810 -0.000000 0.999611 -0.027905 -0.000001 0.999610 -0.027908 -0.000001 0.999610 -0.027908 -0.000005 0.998442 -0.055795 --0.000000 0.998441 -0.055810 -0.000000 0.987396 0.158267 -0.000000 0.987396 0.158267 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 0.987396 0.158267 -0.000000 1.000000 0.000000 -0.000000 0.999610 -0.027908 -0.000001 0.999610 -0.027908 -0.000001 0.999610 -0.027908 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000001 0.999610 -0.027908 -0.000000 0.999610 -0.027908 --0.000001 0.998442 -0.055795 --0.000001 0.998442 -0.055795 -0.000005 0.998442 -0.055795 -0.000001 0.999610 -0.027908 -0.000002 0.998442 -0.055798 --0.000000 0.998441 -0.055815 --0.000000 0.998441 -0.055810 --0.000000 0.998441 -0.055810 -0.000005 0.998442 -0.055795 -0.000002 0.998442 -0.055798 -0.000002 0.998442 -0.055798 -0.000000 0.906973 -0.421189 -0.000000 0.906973 -0.421189 -0.000000 0.906973 -0.421189 --0.000000 0.998441 -0.055815 -0.000002 0.998442 -0.055798 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000001 0.999610 -0.027908 -0.000000 0.999611 -0.027905 -0.000000 0.999611 -0.027905 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.987396 0.000000 0.158268 -0.987396 0.000000 0.158268 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000001 -1.000000 0.000000 0.000000 -0.987396 0.000000 0.158268 -0.999195 0.000001 -0.040116 -0.999799 0.000000 -0.020062 -0.999799 0.000000 -0.020063 -0.999799 0.000000 -0.020063 -0.999196 -0.000000 -0.040095 -0.999195 0.000001 -0.040116 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000001 -1.000000 -0.000000 0.000001 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000001 -1.000000 -0.000000 -0.000001 -1.000000 -0.000000 0.000001 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000001 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -1.000000 -0.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000001 -0.000000 1.000000 0.000001 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 -0.000000 -0.000000 1.000000 -0.000001 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000003 --0.000000 1.000000 -0.000000 --0.000000 1.000000 -0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000001 -0.000000 1.000000 0.000021 --0.000000 1.000000 0.000003 --0.000000 1.000000 0.000003 --0.000000 1.000000 0.000000 --0.000000 1.000000 0.000001 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.293667 0.950362 -0.102818 -0.378489 0.922436 0.076533 --0.466777 0.877351 -0.111237 --0.466777 0.877351 -0.111237 --0.437377 0.898427 0.039117 -0.293667 0.950362 -0.102818 -0.000000 1.000000 0.000002 -0.000000 0.928568 -0.371161 -0.053947 0.933079 -0.355603 -0.053947 0.933079 -0.355603 -0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 --0.083860 0.883048 -0.461729 --0.334821 0.862577 -0.379284 -0.219047 0.944662 0.244197 -0.219047 0.944662 0.244197 -0.058021 0.917041 0.394549 --0.083860 0.883048 -0.461729 --0.278630 0.944534 0.173843 --0.204871 0.931518 0.300504 -0.126855 0.942566 -0.308993 -0.126855 0.942566 -0.308993 -0.199706 0.956891 -0.210898 --0.278630 0.944534 0.173843 --0.437377 0.898427 0.039117 --0.278630 0.944534 0.173843 -0.199706 0.956891 -0.210898 -0.199706 0.956891 -0.210898 -0.293667 0.950362 -0.102818 --0.437377 0.898427 0.039117 --0.000000 0.902777 -0.430109 --0.083860 0.883048 -0.461729 -0.058021 0.917041 0.394549 -0.058021 0.917041 0.394549 --0.000000 0.903393 0.428813 --0.000000 0.902777 -0.430109 -0.219047 0.944662 0.244197 --0.334821 0.862577 -0.379284 --0.466777 0.877351 -0.111237 --0.466777 0.877351 -0.111237 -0.378489 0.922436 0.076533 -0.219047 0.944662 0.244197 --0.204871 0.931518 0.300504 -0.000000 1.000000 0.000002 -0.053947 0.933079 -0.355603 -0.053947 0.933079 -0.355603 -0.126855 0.942566 -0.308993 --0.204871 0.931518 0.300504 -0.984855 0.000001 0.173380 -0.924386 0.345298 0.162108 -0.906193 0.386267 -0.172082 -0.906193 0.386267 -0.172082 -0.973923 0.000000 -0.226877 -0.984855 0.000001 0.173380 --0.965948 0.000000 0.258737 --0.876796 0.404449 0.260095 --0.922754 0.317517 -0.218422 --0.922754 0.317517 -0.218422 --0.972507 0.000000 -0.232874 --0.965948 0.000000 0.258737 -0.000000 0.000000 1.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.165253 0.000000 -0.986251 -0.145080 0.399992 -0.904963 --0.000000 0.389580 -0.920992 --0.000000 0.389580 -0.920992 -0.000000 0.000000 -1.000000 -0.165253 0.000000 -0.986251 --0.661497 0.000000 -0.749948 --0.628453 0.312262 -0.712418 --0.161327 0.320071 -0.933557 --0.161327 0.320071 -0.933557 --0.174458 0.000000 -0.984665 --0.661497 0.000000 -0.749948 -0.139943 0.000000 0.990160 -0.134000 0.341445 0.930301 -0.629331 0.383170 0.676109 -0.629331 0.383170 0.676109 -0.682763 0.000001 0.730640 -0.139943 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 -0.000001 0.480135 -0.877194 --0.472044 0.840449 -0.266121 --0.472044 0.840449 -0.266121 --0.865983 0.000000 -0.500074 -0.000000 0.000000 -1.000000 -0.973923 0.000000 -0.226877 -0.906193 0.386267 -0.172082 -0.686198 0.460064 -0.563448 -0.686198 0.460064 -0.563448 -0.766123 0.000000 -0.642694 -0.973923 0.000000 -0.226877 --0.865983 0.000000 -0.500074 --0.472044 0.840449 -0.266121 --0.876796 0.404449 0.260095 --0.876796 0.404449 0.260095 --0.965948 0.000000 0.258737 --0.865983 0.000000 -0.500074 --0.000000 0.000000 1.000000 --0.000000 0.335574 0.942014 -0.134000 0.341445 0.930301 -0.134000 0.341445 0.930301 -0.139943 0.000000 0.990160 --0.000000 0.000000 1.000000 --0.174458 0.000000 -0.984665 --0.161327 0.320071 -0.933557 --0.000000 0.335181 -0.942154 --0.000000 0.335181 -0.942154 -0.000000 0.000000 -1.000000 --0.174458 0.000000 -0.984665 --0.972507 0.000000 -0.232874 --0.922754 0.317517 -0.218422 --0.628453 0.312262 -0.712418 --0.628453 0.312262 -0.712418 --0.661497 0.000000 -0.749948 --0.972507 0.000000 -0.232874 -0.682763 0.000001 0.730640 -0.629331 0.383170 0.676109 -0.924386 0.345298 0.162108 -0.924386 0.345298 0.162108 -0.984855 0.000001 0.173380 -0.682763 0.000001 0.730640 -0.446772 0.000000 -0.894648 -0.391985 0.437360 -0.809360 -0.145080 0.399992 -0.904963 -0.145080 0.399992 -0.904963 -0.165253 0.000000 -0.986251 -0.446772 0.000000 -0.894648 -0.766123 0.000000 -0.642694 -0.686198 0.460064 -0.563448 -0.391985 0.437360 -0.809360 -0.391985 0.437360 -0.809360 -0.446772 0.000000 -0.894648 -0.766123 0.000000 -0.642694 --0.437377 0.898427 0.039117 --0.466777 0.877351 -0.111237 --0.922754 0.317517 -0.218422 --0.922754 0.317517 -0.218422 --0.876796 0.404449 0.260095 --0.437377 0.898427 0.039117 -0.378489 0.922436 0.076533 -0.293667 0.950362 -0.102818 -0.906193 0.386267 -0.172082 -0.906193 0.386267 -0.172082 -0.924386 0.345298 0.162108 -0.378489 0.922436 0.076533 -0.000000 0.960502 0.278273 -0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 --0.016761 0.961573 0.274037 -0.000000 0.960502 0.278273 -0.145080 0.399992 -0.904963 -0.053947 0.933079 -0.355603 -0.000000 0.928568 -0.371161 -0.000000 0.928568 -0.371161 --0.000000 0.389580 -0.920992 -0.145080 0.399992 -0.904963 -0.058021 0.917041 0.394549 -0.219047 0.944662 0.244197 -0.629331 0.383170 0.676109 -0.629331 0.383170 0.676109 -0.134000 0.341445 0.930301 -0.058021 0.917041 0.394549 --0.334821 0.862577 -0.379284 --0.083860 0.883048 -0.461729 --0.161327 0.320071 -0.933557 --0.161327 0.320071 -0.933557 --0.628453 0.312262 -0.712418 --0.334821 0.862577 -0.379284 -0.199706 0.956891 -0.210898 -0.126855 0.942566 -0.308993 -0.391985 0.437360 -0.809360 -0.391985 0.437360 -0.809360 -0.686198 0.460064 -0.563448 -0.199706 0.956891 -0.210898 -0.293667 0.950362 -0.102818 -0.199706 0.956891 -0.210898 -0.686198 0.460064 -0.563448 -0.686198 0.460064 -0.563448 -0.906193 0.386267 -0.172082 -0.293667 0.950362 -0.102818 --0.278630 0.944534 0.173843 --0.437377 0.898427 0.039117 --0.876796 0.404449 0.260095 --0.876796 0.404449 0.260095 --0.472044 0.840449 -0.266121 --0.278630 0.944534 0.173843 --0.000000 0.903393 0.428813 -0.058021 0.917041 0.394549 -0.134000 0.341445 0.930301 -0.134000 0.341445 0.930301 --0.000000 0.335574 0.942014 --0.000000 0.903393 0.428813 --0.161327 0.320071 -0.933557 --0.083860 0.883048 -0.461729 --0.000000 0.902777 -0.430109 --0.000000 0.902777 -0.430109 --0.000000 0.335181 -0.942154 --0.161327 0.320071 -0.933557 -0.629331 0.383170 0.676109 -0.219047 0.944662 0.244197 -0.378489 0.922436 0.076533 -0.378489 0.922436 0.076533 -0.924386 0.345298 0.162108 -0.629331 0.383170 0.676109 --0.922754 0.317517 -0.218422 --0.466777 0.877351 -0.111237 --0.334821 0.862577 -0.379284 --0.334821 0.862577 -0.379284 --0.628453 0.312262 -0.712418 --0.922754 0.317517 -0.218422 -0.126855 0.942566 -0.308993 -0.053947 0.933079 -0.355603 -0.145080 0.399992 -0.904963 -0.145080 0.399992 -0.904963 -0.391985 0.437360 -0.809360 -0.126855 0.942566 -0.308993 --0.204871 0.931518 0.300504 --0.472044 0.840449 -0.266121 --0.016761 0.961573 0.274037 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 0.482408 0.875946 -0.000000 0.960502 0.278273 --0.016761 0.961573 0.274037 --0.016761 0.961573 0.274037 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 --0.016761 0.961573 0.274037 -0.000000 0.999997 -0.002593 -0.000000 0.999997 -0.002593 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 --0.016761 0.961573 0.274037 -0.000000 1.000000 0.000002 --0.204871 0.931518 0.300504 --0.204871 0.931518 0.300504 --0.278630 0.944534 0.173843 --0.472044 0.840449 -0.266121 -0.000001 0.480135 -0.877194 -0.000000 0.999997 -0.002593 --0.016761 0.961573 0.274037 --0.016761 0.961573 0.274037 --0.472044 0.840449 -0.266121 -0.000001 0.480135 -0.877194 --0.293669 0.950361 -0.102818 -0.437376 0.898427 0.039117 -0.466777 0.877352 -0.111236 -0.466777 0.877352 -0.111236 --0.378490 0.922436 0.076533 --0.293669 0.950361 -0.102818 -0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 --0.053947 0.933079 -0.355603 --0.053947 0.933079 -0.355603 -0.000000 0.928568 -0.371161 -0.000000 1.000000 0.000002 -0.083860 0.883048 -0.461729 --0.058021 0.917041 0.394549 --0.219047 0.944662 0.244197 --0.219047 0.944662 0.244197 -0.334821 0.862576 -0.379284 -0.083860 0.883048 -0.461729 -0.278630 0.944534 0.173843 --0.199706 0.956891 -0.210898 --0.126855 0.942566 -0.308994 --0.126855 0.942566 -0.308994 -0.204871 0.931518 0.300504 -0.278630 0.944534 0.173843 -0.437376 0.898427 0.039117 --0.293669 0.950361 -0.102818 --0.199706 0.956891 -0.210898 --0.199706 0.956891 -0.210898 -0.278630 0.944534 0.173843 -0.437376 0.898427 0.039117 --0.000000 0.902777 -0.430109 --0.000000 0.903393 0.428813 --0.058021 0.917041 0.394549 --0.058021 0.917041 0.394549 -0.083860 0.883048 -0.461729 --0.000000 0.902777 -0.430109 --0.219047 0.944662 0.244197 --0.378490 0.922436 0.076533 -0.466777 0.877352 -0.111236 -0.466777 0.877352 -0.111236 -0.334821 0.862576 -0.379284 --0.219047 0.944662 0.244197 -0.204871 0.931518 0.300504 --0.126855 0.942566 -0.308994 --0.053947 0.933079 -0.355603 --0.053947 0.933079 -0.355603 -0.000000 1.000000 0.000002 -0.204871 0.931518 0.300504 --0.984855 0.000000 0.173382 --0.973923 0.000000 -0.226877 --0.906194 0.386265 -0.172082 --0.906194 0.386265 -0.172082 --0.924387 0.345297 0.162109 --0.984855 0.000000 0.173382 -0.965948 0.000000 0.258737 -0.972507 0.000000 -0.232875 -0.922754 0.317518 -0.218422 -0.922754 0.317518 -0.218422 -0.876797 0.404449 0.260094 -0.965948 0.000000 0.258737 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.000000 1.000000 --0.165253 0.000000 -0.986251 -0.000000 0.000000 -1.000000 --0.000000 0.389580 -0.920992 --0.000000 0.389580 -0.920992 --0.145080 0.399992 -0.904963 --0.165253 0.000000 -0.986251 -0.661497 0.000000 -0.749948 -0.174458 0.000000 -0.984665 -0.161327 0.320071 -0.933557 -0.161327 0.320071 -0.933557 -0.628453 0.312262 -0.712418 -0.661497 0.000000 -0.749948 --0.139942 0.000000 0.990160 --0.682761 0.000000 0.730642 --0.629331 0.383170 0.676109 --0.629331 0.383170 0.676109 --0.133999 0.341445 0.930301 --0.139942 0.000000 0.990160 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.000000 1.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 -0.865983 0.000000 -0.500074 -0.472044 0.840449 -0.266121 -0.472044 0.840449 -0.266121 --0.000001 0.480135 -0.877194 -0.000000 0.000000 -1.000000 --0.973923 0.000000 -0.226877 --0.766123 0.000000 -0.642694 --0.686198 0.460063 -0.563448 --0.686198 0.460063 -0.563448 --0.906194 0.386265 -0.172082 --0.973923 0.000000 -0.226877 -0.865983 0.000000 -0.500074 -0.965948 0.000000 0.258737 -0.876797 0.404449 0.260094 -0.876797 0.404449 0.260094 -0.472044 0.840449 -0.266121 -0.865983 0.000000 -0.500074 --0.000000 0.000000 1.000000 --0.139942 0.000000 0.990160 --0.133999 0.341445 0.930301 --0.133999 0.341445 0.930301 --0.000000 0.335574 0.942014 --0.000000 0.000000 1.000000 -0.174458 0.000000 -0.984665 -0.000000 0.000000 -1.000000 --0.000000 0.335181 -0.942154 --0.000000 0.335181 -0.942154 -0.161327 0.320071 -0.933557 -0.174458 0.000000 -0.984665 -0.972507 0.000000 -0.232875 -0.661497 0.000000 -0.749948 -0.628453 0.312262 -0.712418 -0.628453 0.312262 -0.712418 -0.922754 0.317518 -0.218422 -0.972507 0.000000 -0.232875 --0.682761 0.000000 0.730642 --0.984855 0.000000 0.173382 --0.924387 0.345297 0.162109 --0.924387 0.345297 0.162109 --0.629331 0.383170 0.676109 --0.682761 0.000000 0.730642 --0.446771 0.000000 -0.894648 --0.165253 0.000000 -0.986251 --0.145080 0.399992 -0.904963 --0.145080 0.399992 -0.904963 --0.391985 0.437360 -0.809361 --0.446771 0.000000 -0.894648 --0.766123 0.000000 -0.642694 --0.446771 0.000000 -0.894648 --0.391985 0.437360 -0.809361 --0.391985 0.437360 -0.809361 --0.686198 0.460063 -0.563448 --0.766123 0.000000 -0.642694 -0.437376 0.898427 0.039117 -0.876797 0.404449 0.260094 -0.922754 0.317518 -0.218422 -0.922754 0.317518 -0.218422 -0.466777 0.877352 -0.111236 -0.437376 0.898427 0.039117 --0.378490 0.922436 0.076533 --0.924387 0.345297 0.162109 --0.906194 0.386265 -0.172082 --0.906194 0.386265 -0.172082 --0.293669 0.950361 -0.102818 --0.378490 0.922436 0.076533 -0.000000 0.960502 0.278273 -0.016761 0.961573 0.274037 -0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 -0.000000 1.000000 0.000002 -0.000000 0.960502 0.278273 --0.145080 0.399992 -0.904963 --0.000000 0.389580 -0.920992 -0.000000 0.928568 -0.371161 -0.000000 0.928568 -0.371161 --0.053947 0.933079 -0.355603 --0.145080 0.399992 -0.904963 --0.058021 0.917041 0.394549 --0.133999 0.341445 0.930301 --0.629331 0.383170 0.676109 --0.629331 0.383170 0.676109 --0.219047 0.944662 0.244197 --0.058021 0.917041 0.394549 -0.334821 0.862576 -0.379284 -0.628453 0.312262 -0.712418 -0.161327 0.320071 -0.933557 -0.161327 0.320071 -0.933557 -0.083860 0.883048 -0.461729 -0.334821 0.862576 -0.379284 --0.199706 0.956891 -0.210898 --0.686198 0.460063 -0.563448 --0.391985 0.437360 -0.809361 --0.391985 0.437360 -0.809361 --0.126855 0.942566 -0.308994 --0.199706 0.956891 -0.210898 --0.293669 0.950361 -0.102818 --0.906194 0.386265 -0.172082 --0.686198 0.460063 -0.563448 --0.686198 0.460063 -0.563448 --0.199706 0.956891 -0.210898 --0.293669 0.950361 -0.102818 -0.278630 0.944534 0.173843 -0.472044 0.840449 -0.266121 -0.876797 0.404449 0.260094 -0.876797 0.404449 0.260094 -0.437376 0.898427 0.039117 -0.278630 0.944534 0.173843 --0.000000 0.903393 0.428813 --0.000000 0.335574 0.942014 --0.133999 0.341445 0.930301 --0.133999 0.341445 0.930301 --0.058021 0.917041 0.394549 --0.000000 0.903393 0.428813 -0.161327 0.320071 -0.933557 --0.000000 0.335181 -0.942154 --0.000000 0.902777 -0.430109 --0.000000 0.902777 -0.430109 -0.083860 0.883048 -0.461729 -0.161327 0.320071 -0.933557 --0.629331 0.383170 0.676109 --0.924387 0.345297 0.162109 --0.378490 0.922436 0.076533 --0.378490 0.922436 0.076533 --0.219047 0.944662 0.244197 --0.629331 0.383170 0.676109 -0.922754 0.317518 -0.218422 -0.628453 0.312262 -0.712418 -0.334821 0.862576 -0.379284 -0.334821 0.862576 -0.379284 -0.466777 0.877352 -0.111236 -0.922754 0.317518 -0.218422 --0.126855 0.942566 -0.308994 --0.391985 0.437360 -0.809361 --0.145080 0.399992 -0.904963 --0.145080 0.399992 -0.904963 --0.053947 0.933079 -0.355603 --0.126855 0.942566 -0.308994 -0.204871 0.931518 0.300504 -0.016761 0.961573 0.274037 -0.472044 0.840449 -0.266121 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.016761 0.961573 0.274037 -0.016761 0.961573 0.274037 -0.000000 0.960502 0.278273 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.482408 0.875946 -0.000000 0.999997 -0.002593 -0.000000 0.999997 -0.002593 -0.016761 0.961573 0.274037 -0.000000 0.482408 0.875946 -0.016761 0.961573 0.274037 -0.204871 0.931518 0.300504 -0.000000 1.000000 0.000002 -0.204871 0.931518 0.300504 -0.472044 0.840449 -0.266121 -0.278630 0.944534 0.173843 --0.000001 0.480135 -0.877194 -0.472044 0.840449 -0.266121 -0.016761 0.961573 0.274037 -0.016761 0.961573 0.274037 -0.000000 0.999997 -0.002593 --0.000001 0.480135 -0.877194 -0.162115 0.000000 0.986772 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.162115 0.000000 0.986772 -0.162115 0.000000 0.986772 -0.162115 0.000000 0.986772 -0.162115 -0.000000 0.986772 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.162115 0.000000 0.986772 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 --0.987088 0.160179 0.000000 --0.987088 0.160179 0.000000 --0.987088 0.160179 0.000000 --1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.090945 0.995856 -0.000000 0.136135 0.990690 -0.000000 0.136135 0.990690 -0.000000 0.090945 0.995856 -0.000000 0.090945 0.995856 -0.000000 0.136135 0.990690 --0.011116 0.125442 0.992039 -0.000000 0.090945 0.995856 -0.000000 0.136135 0.990690 --0.011116 0.125442 0.992039 -0.000000 0.136135 0.990690 --0.024596 0.112431 0.993355 --0.962160 0.000000 0.272486 --0.962160 0.000000 0.272486 --0.943771 0.131277 0.303417 --0.943771 0.131277 0.303417 --0.934508 0.171543 0.311877 --0.962160 0.000000 0.272486 --0.067300 0.649220 -0.757617 --0.128270 0.611138 -0.781062 -0.000000 0.686714 -0.726928 -0.000000 0.686714 -0.726928 -0.000000 0.686714 -0.726928 --0.067300 0.649220 -0.757617 --0.163219 0.984624 -0.062245 -0.000000 0.998433 -0.055964 -0.000000 0.998433 -0.055963 -0.000000 0.998433 -0.055963 --0.159866 0.985177 -0.062205 --0.163219 0.984624 -0.062245 --0.999054 -0.000000 -0.043479 --0.985762 0.159898 -0.052024 --0.986521 0.155074 -0.052242 --0.986521 0.155074 -0.052242 --0.999027 0.000000 -0.044103 --0.999054 -0.000000 -0.043479 --0.999038 0.000000 -0.043860 --0.999038 0.000000 -0.043860 --0.999038 0.000000 -0.043860 --0.999038 0.000000 -0.043860 --0.999038 0.000000 -0.043860 --0.999038 0.000000 -0.043860 --0.999054 0.000000 -0.043479 --0.999054 -0.000000 -0.043486 --0.999027 0.000000 -0.044102 --0.999027 0.000000 -0.044102 --0.999027 0.000000 -0.044103 --0.999054 0.000000 -0.043479 --0.691128 0.000001 -0.722733 --0.613769 0.129384 -0.778812 --0.653289 0.067036 -0.754135 --0.653289 0.067036 -0.754135 --0.691128 0.000001 -0.722732 --0.691128 0.000001 -0.722733 --0.682748 0.000000 -0.730654 --0.682748 0.000000 -0.730654 --0.682748 0.000000 -0.730654 --0.682748 0.000000 -0.730654 --0.682748 0.000000 -0.730654 --0.682748 0.000000 -0.730654 --0.691128 0.000000 -0.722732 --0.691128 0.000000 -0.722732 --0.691128 0.000000 -0.722732 --0.691128 0.000000 -0.722732 --0.691128 0.000000 -0.722733 --0.691128 0.000000 -0.722732 --0.217362 -0.970528 -0.104062 --0.217362 -0.970528 -0.104062 --0.217362 -0.970528 -0.104062 --0.216100 -0.970831 -0.103869 --0.216100 -0.970831 -0.103869 --0.216100 -0.970831 -0.103869 --0.205506 -0.932072 -0.298345 --0.205506 -0.932072 -0.298345 --0.205506 -0.932072 -0.298345 --0.207347 -0.926207 -0.314878 --0.207347 -0.926207 -0.314878 --0.207347 -0.926207 -0.314878 --0.207482 0.926773 -0.313117 --0.207482 0.926773 -0.313117 --0.207482 0.926773 -0.313117 --0.211048 0.929400 -0.302779 --0.211048 0.929400 -0.302779 --0.211048 0.929400 -0.302779 --0.216091 0.970684 -0.105248 --0.216091 0.970684 -0.105248 --0.216091 0.970684 -0.105248 --0.217176 0.970455 -0.105127 --0.217176 0.970455 -0.105127 --0.217176 0.970455 -0.105127 --0.194186 -0.000000 -0.980965 --0.194186 -0.000000 -0.980965 --0.194186 -0.000000 -0.980965 --0.194187 0.000000 -0.980965 --0.194187 0.000000 -0.980965 --0.194187 0.000000 -0.980965 --0.217172 -0.970440 -0.105272 --0.217172 -0.970440 -0.105272 --0.217172 -0.970440 -0.105272 --0.216066 -0.970705 -0.105103 --0.216066 -0.970705 -0.105102 --0.216066 -0.970705 -0.105103 --0.210116 -0.925296 -0.315719 --0.210116 -0.925296 -0.315719 --0.210116 -0.925296 -0.315719 --0.208395 -0.930880 -0.300057 --0.208395 -0.930880 -0.300057 --0.208395 -0.930880 -0.300057 --0.156367 0.985741 -0.062154 --0.159866 0.985177 -0.062205 -0.000000 0.998433 -0.055963 -0.000000 0.998433 -0.055963 -0.000000 0.998433 -0.055963 --0.156367 0.985741 -0.062154 --0.160183 0.987087 0.000000 --0.160183 0.987087 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 --0.160183 0.987087 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 --0.127993 0.011020 0.991714 --0.113787 0.025124 0.993187 --0.139053 0.000000 0.990285 --0.139053 0.000000 0.990285 --0.139053 0.000000 0.990285 --0.127993 0.011020 0.991714 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.999067 0.000000 -0.043190 --0.984967 0.164786 -0.051814 --0.985762 0.159898 -0.052024 --0.999067 0.000000 -0.043190 --0.985762 0.159898 -0.052024 --0.999054 -0.000000 -0.043479 --0.999067 0.000000 -0.043190 --0.999054 -0.000000 -0.043479 --0.999054 -0.000000 -0.043486 --0.999067 0.000000 -0.043190 --0.999054 -0.000000 -0.043486 --0.999054 0.000000 -0.043479 --0.999067 0.000000 -0.043190 --0.999054 0.000000 -0.043479 --0.999067 0.000000 -0.043191 --0.194281 -0.000000 -0.980946 --0.194281 -0.000000 -0.980946 --0.194281 -0.000000 -0.980946 --0.194282 0.000000 -0.980946 --0.194282 0.000000 -0.980946 --0.194282 0.000000 -0.980946 -0.000000 0.964133 0.265420 --0.172666 0.936050 0.306588 --0.130685 0.945774 0.297376 --0.130685 0.945774 0.297376 -0.000000 0.964133 0.265419 -0.000000 0.964133 0.265420 --0.130685 0.945774 0.297376 -0.000000 0.964133 0.265419 --0.000000 0.964133 0.265419 --0.000000 0.964133 0.265419 -0.000000 0.964133 0.265419 --0.130685 0.945774 0.297376 -0.000000 0.964133 0.265420 -0.000000 0.964133 0.265420 --0.000000 0.964133 0.265419 --0.000000 0.964133 0.265419 -0.000000 0.964133 0.265419 -0.000000 0.964133 0.265420 -0.000000 0.090945 0.995856 -0.000000 0.090945 0.995856 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.090945 0.995856 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.705506 0.705204 -0.070341 --0.985762 0.159898 -0.052024 --0.984967 0.164786 -0.051814 --0.984967 0.164786 -0.051814 --0.703602 0.707133 -0.070051 --0.705506 0.705204 -0.070341 --0.707109 0.707104 0.000000 --0.160183 0.987087 0.000000 --0.160183 0.987087 0.000000 --0.160183 0.987087 0.000000 --0.707109 0.707104 0.000000 --0.707109 0.707104 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 --0.068966 0.069265 0.995212 --0.113787 0.025124 0.993187 --0.127993 0.011020 0.991714 --0.127993 0.011020 0.991714 --0.069489 0.068753 0.995211 --0.068966 0.069265 0.995212 --0.656525 0.658835 0.367303 --0.130685 0.945774 0.297376 --0.172666 0.936050 0.306588 --0.172666 0.936050 0.306588 --0.658526 0.656828 0.367316 --0.656525 0.658835 0.367303 --0.393996 0.394837 -0.829983 --0.128270 0.611138 -0.781062 --0.067300 0.649220 -0.757617 --0.067300 0.649220 -0.757617 --0.395300 0.393544 -0.829977 --0.393996 0.394837 -0.829983 --0.707078 0.703597 -0.070651 --0.986521 0.155074 -0.052242 --0.985762 0.159898 -0.052024 --0.985762 0.159898 -0.052024 --0.705506 0.705204 -0.070341 --0.707078 0.703597 -0.070651 --0.159866 0.985177 -0.062205 --0.705506 0.705204 -0.070341 --0.703602 0.707133 -0.070051 --0.703602 0.707133 -0.070051 --0.163219 0.984624 -0.062245 --0.159866 0.985177 -0.062205 --0.987088 0.160179 0.000000 --0.707109 0.707104 0.000000 --0.707109 0.707104 0.000000 --0.707109 0.707104 0.000000 --0.987088 0.160179 0.000000 --0.987088 0.160179 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 --0.024596 0.112431 0.993355 --0.068966 0.069265 0.995212 --0.069489 0.068753 0.995211 --0.069489 0.068753 0.995211 --0.011116 0.125442 0.992039 --0.024596 0.112431 0.993355 --0.943771 0.131277 0.303417 --0.656525 0.658835 0.367303 --0.658526 0.656828 0.367316 --0.658526 0.656828 0.367316 --0.934508 0.171543 0.311877 --0.943771 0.131277 0.303417 --0.613769 0.129384 -0.778812 --0.393996 0.394837 -0.829983 --0.395300 0.393544 -0.829977 --0.395300 0.393544 -0.829977 --0.653289 0.067036 -0.754135 --0.613769 0.129384 -0.778812 --0.156367 0.985741 -0.062154 --0.707078 0.703597 -0.070651 --0.705506 0.705204 -0.070341 --0.705506 0.705204 -0.070341 --0.159866 0.985177 -0.062205 --0.156367 0.985741 -0.062154 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --0.999042 0.000000 -0.043762 --1.000000 0.000000 0.000000 --0.987087 -0.160185 0.000000 --0.987087 -0.160185 0.000000 --0.987087 -0.160185 0.000000 --1.000000 0.000000 0.000000 --1.000000 0.000000 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 --0.011116 -0.125442 0.992039 --0.024597 -0.112430 0.993355 -0.000000 -0.136135 0.990690 -0.000000 -0.136135 0.990690 -0.000000 -0.136135 0.990690 -0.000000 -0.090945 0.995856 -0.000000 -0.136135 0.990690 -0.000000 -0.090945 0.995856 -0.000000 -0.090945 0.995856 --0.011116 -0.125442 0.992039 -0.000000 -0.136135 0.990690 -0.000000 -0.090945 0.995856 --0.962160 0.000000 0.272486 --0.934506 -0.171549 0.311880 --0.943772 -0.131273 0.303417 --0.943772 -0.131273 0.303417 --0.962160 0.000000 0.272486 --0.962160 0.000000 0.272486 --0.067299 -0.649220 -0.757617 -0.000000 -0.686714 -0.726928 -0.000000 -0.686714 -0.726928 -0.000000 -0.686714 -0.726928 --0.128271 -0.611136 -0.781063 --0.067299 -0.649220 -0.757617 --0.163219 -0.984624 -0.062245 --0.159864 -0.985177 -0.062205 --0.000000 -0.998433 -0.055963 --0.000000 -0.998433 -0.055963 -0.000000 -0.998433 -0.055964 --0.163219 -0.984624 -0.062245 --0.999054 0.000000 -0.043479 --0.999027 0.000000 -0.044102 --0.986520 -0.155080 -0.052242 --0.986520 -0.155080 -0.052242 --0.985763 -0.159892 -0.052023 --0.999054 0.000000 -0.043479 --0.999038 0.000000 -0.043860 --0.999038 0.000001 -0.043860 --0.999038 0.000001 -0.043860 --0.999038 0.000001 -0.043860 --0.999038 0.000000 -0.043860 --0.999038 0.000000 -0.043860 --0.999054 -0.000000 -0.043479 --0.999027 0.000000 -0.044103 --0.999027 -0.000000 -0.044102 --0.999027 -0.000000 -0.044102 --0.999054 0.000000 -0.043486 --0.999054 -0.000000 -0.043479 --0.691122 0.000000 -0.722738 --0.691122 0.000000 -0.722738 --0.653287 -0.067038 -0.754137 --0.653287 -0.067038 -0.754137 --0.613766 -0.129388 -0.778813 --0.691122 0.000000 -0.722738 --0.682748 0.000000 -0.730654 --0.682748 0.000000 -0.730654 --0.682742 0.000001 -0.730659 --0.682742 0.000001 -0.730659 --0.682742 0.000001 -0.730659 --0.682748 0.000000 -0.730654 --0.691128 0.000000 -0.722732 --0.691128 0.000000 -0.722733 --0.691128 0.000000 -0.722732 --0.691128 0.000000 -0.722732 --0.691128 0.000000 -0.722732 --0.691128 0.000000 -0.722732 --0.216100 0.970831 -0.103869 --0.216100 0.970831 -0.103869 --0.216100 0.970831 -0.103869 --0.217362 0.970528 -0.104062 --0.217362 0.970528 -0.104062 --0.217362 0.970528 -0.104062 --0.207347 0.926207 -0.314879 --0.207347 0.926207 -0.314879 --0.207347 0.926207 -0.314879 --0.205506 0.932072 -0.298345 --0.205506 0.932072 -0.298345 --0.205506 0.932072 -0.298345 --0.211048 -0.929400 -0.302779 --0.211048 -0.929400 -0.302779 --0.211048 -0.929400 -0.302779 --0.207481 -0.926773 -0.313119 --0.207481 -0.926773 -0.313119 --0.207481 -0.926773 -0.313119 --0.217175 -0.970455 -0.105127 --0.217175 -0.970455 -0.105127 --0.217175 -0.970455 -0.105127 --0.216091 -0.970684 -0.105248 --0.216091 -0.970684 -0.105248 --0.216091 -0.970684 -0.105248 --0.194187 0.000000 -0.980965 --0.194187 0.000000 -0.980965 --0.194187 0.000000 -0.980965 --0.194186 0.000000 -0.980965 --0.194186 0.000000 -0.980965 --0.194186 0.000000 -0.980965 --0.216066 0.970705 -0.105102 --0.216066 0.970705 -0.105102 --0.216066 0.970705 -0.105102 --0.217172 0.970440 -0.105272 --0.217172 0.970440 -0.105272 --0.217172 0.970440 -0.105272 --0.208395 0.930879 -0.300060 --0.208395 0.930879 -0.300060 --0.208395 0.930879 -0.300060 --0.210116 0.925295 -0.315722 --0.210116 0.925295 -0.315722 --0.210116 0.925295 -0.315722 --0.156369 -0.985741 -0.062154 -0.000000 -0.998433 -0.055963 --0.000000 -0.998433 -0.055963 --0.000000 -0.998433 -0.055963 --0.159864 -0.985177 -0.062205 --0.156369 -0.985741 -0.062154 --0.160185 -0.987087 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 --0.160185 -0.987087 0.000000 --0.160185 -0.987087 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 --0.127993 -0.011020 0.991714 --0.139053 0.000000 0.990285 --0.139053 0.000000 0.990285 --0.139053 0.000000 0.990285 --0.113787 -0.025125 0.993187 --0.127993 -0.011020 0.991714 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.682999 0.000000 -0.730420 --0.999067 0.000000 -0.043190 --0.999067 0.000000 -0.043191 --0.999054 -0.000000 -0.043479 --0.999067 0.000000 -0.043190 --0.999054 -0.000000 -0.043479 --0.999054 0.000000 -0.043486 --0.999067 0.000000 -0.043190 --0.999054 0.000000 -0.043486 --0.999054 0.000000 -0.043479 --0.999067 0.000000 -0.043190 --0.999054 0.000000 -0.043479 --0.985763 -0.159892 -0.052023 --0.999067 0.000000 -0.043190 --0.985763 -0.159892 -0.052023 --0.984968 -0.164785 -0.051812 --0.194282 0.000000 -0.980946 --0.194282 0.000000 -0.980946 --0.194282 0.000000 -0.980946 --0.194281 0.000000 -0.980946 --0.194281 0.000000 -0.980946 --0.194281 0.000000 -0.980946 -0.000000 -0.964133 0.265420 -0.000000 -0.964133 0.265419 --0.130684 -0.945775 0.297375 --0.130684 -0.945775 0.297375 --0.172666 -0.936050 0.306588 -0.000000 -0.964133 0.265420 --0.130684 -0.945775 0.297375 -0.000000 -0.964133 0.265419 --0.000000 -0.964133 0.265419 --0.000000 -0.964133 0.265419 -0.000000 -0.964133 0.265419 --0.130684 -0.945775 0.297375 -0.000000 -0.964133 0.265420 -0.000000 -0.964133 0.265419 --0.000000 -0.964133 0.265419 --0.000000 -0.964133 0.265419 -0.000000 -0.964133 0.265420 -0.000000 -0.964133 0.265420 -0.000000 -0.090945 0.995856 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 -0.090945 0.995856 -0.000000 -0.090945 0.995856 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.974308 0.000000 -0.225219 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.975766 0.000000 -0.218815 --0.705509 -0.705202 -0.070340 --0.703602 -0.707134 -0.070049 --0.984968 -0.164785 -0.051812 --0.984968 -0.164785 -0.051812 --0.985763 -0.159892 -0.052023 --0.705509 -0.705202 -0.070340 --0.707106 -0.707107 0.000000 --0.707106 -0.707107 0.000000 --0.160185 -0.987087 0.000000 --0.160185 -0.987087 0.000000 --0.160185 -0.987087 0.000000 --0.707106 -0.707107 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 --0.068965 -0.069266 0.995212 --0.069489 -0.068754 0.995211 --0.127993 -0.011020 0.991714 --0.127993 -0.011020 0.991714 --0.113787 -0.025125 0.993187 --0.068965 -0.069266 0.995212 --0.656529 -0.658832 0.367302 --0.658522 -0.656831 0.367316 --0.172666 -0.936050 0.306588 --0.172666 -0.936050 0.306588 --0.130684 -0.945775 0.297375 --0.656529 -0.658832 0.367302 --0.393994 -0.394838 -0.829983 --0.395296 -0.393547 -0.829977 --0.067299 -0.649220 -0.757617 --0.067299 -0.649220 -0.757617 --0.128271 -0.611136 -0.781063 --0.393994 -0.394838 -0.829983 --0.707075 -0.703600 -0.070651 --0.705509 -0.705202 -0.070340 --0.985763 -0.159892 -0.052023 --0.985763 -0.159892 -0.052023 --0.986520 -0.155080 -0.052242 --0.707075 -0.703600 -0.070651 --0.159864 -0.985177 -0.062205 --0.163219 -0.984624 -0.062245 --0.703602 -0.707134 -0.070049 --0.703602 -0.707134 -0.070049 --0.705509 -0.705202 -0.070340 --0.159864 -0.985177 -0.062205 --0.987087 -0.160185 0.000000 --0.987087 -0.160185 0.000000 --0.707106 -0.707107 0.000000 --0.707106 -0.707107 0.000000 --0.707106 -0.707107 0.000000 --0.987087 -0.160185 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 --0.024597 -0.112430 0.993355 --0.011116 -0.125442 0.992039 --0.069489 -0.068754 0.995211 --0.069489 -0.068754 0.995211 --0.068965 -0.069266 0.995212 --0.024597 -0.112430 0.993355 --0.943772 -0.131273 0.303417 --0.934506 -0.171549 0.311880 --0.658522 -0.656831 0.367316 --0.658522 -0.656831 0.367316 --0.656529 -0.658832 0.367302 --0.943772 -0.131273 0.303417 --0.613766 -0.129388 -0.778813 --0.653287 -0.067038 -0.754137 --0.395296 -0.393547 -0.829977 --0.395296 -0.393547 -0.829977 --0.393994 -0.394838 -0.829983 --0.613766 -0.129388 -0.778813 --0.156369 -0.985741 -0.062154 --0.159864 -0.985177 -0.062205 --0.705509 -0.705202 -0.070340 --0.705509 -0.705202 -0.070340 --0.707075 -0.703600 -0.070651 --0.156369 -0.985741 -0.062154 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -1.000000 -0.000000 0.000000 -0.987087 0.160182 0.000000 -0.987087 0.160182 0.000000 -0.987087 0.160182 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.011116 0.125442 0.992039 -0.024597 0.112430 0.993355 -0.000000 0.136135 0.990690 -0.000000 0.136135 0.990690 -0.000000 0.136135 0.990690 -0.000000 0.090945 0.995856 -0.000000 0.136135 0.990690 -0.000000 0.090945 0.995856 -0.000000 0.090945 0.995856 -0.011116 0.125442 0.992039 -0.000000 0.136135 0.990690 -0.000000 0.090945 0.995856 -0.962160 -0.000000 0.272486 -0.934506 0.171549 0.311880 -0.943771 0.131276 0.303418 -0.943771 0.131276 0.303418 -0.962160 0.000000 0.272486 -0.962160 -0.000000 0.272486 -0.067299 0.649221 -0.757617 -0.000000 0.686714 -0.726928 -0.000000 0.686714 -0.726928 -0.000000 0.686714 -0.726928 -0.128272 0.611135 -0.781063 -0.067299 0.649221 -0.757617 -0.163218 0.984625 -0.062245 -0.159865 0.985177 -0.062205 -0.000000 0.998433 -0.055963 -0.000000 0.998433 -0.055963 -0.000000 0.998433 -0.055964 -0.163218 0.984625 -0.062245 -0.999054 0.000000 -0.043479 -0.999027 0.000001 -0.044102 -0.986520 0.155080 -0.052242 -0.986520 0.155080 -0.052242 -0.985763 0.159892 -0.052024 -0.999054 0.000000 -0.043479 -0.999038 -0.000000 -0.043860 -0.999038 -0.000001 -0.043860 -0.999038 -0.000001 -0.043860 -0.999038 -0.000001 -0.043860 -0.999038 0.000000 -0.043860 -0.999038 -0.000000 -0.043860 -0.999054 0.000000 -0.043479 -0.999027 0.000000 -0.044102 -0.999027 0.000000 -0.044102 -0.999027 0.000000 -0.044102 -0.999054 -0.000000 -0.043483 -0.999054 0.000000 -0.043479 -0.691122 0.000000 -0.722738 -0.691122 0.000000 -0.722738 -0.653290 0.067038 -0.754134 -0.653290 0.067038 -0.754134 -0.613770 0.129389 -0.778810 -0.691122 0.000000 -0.722738 -0.682748 -0.000000 -0.730654 -0.682748 0.000000 -0.730654 -0.682742 -0.000001 -0.730659 -0.682742 -0.000001 -0.730659 -0.682742 -0.000001 -0.730659 -0.682748 -0.000000 -0.730654 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.216100 -0.970831 -0.103869 -0.216100 -0.970831 -0.103869 -0.216100 -0.970831 -0.103869 -0.217361 -0.970528 -0.104062 -0.217361 -0.970528 -0.104062 -0.217361 -0.970528 -0.104062 -0.207346 -0.926207 -0.314877 -0.207346 -0.926207 -0.314877 -0.207346 -0.926207 -0.314877 -0.205506 -0.932071 -0.298347 -0.205506 -0.932071 -0.298347 -0.205506 -0.932071 -0.298346 -0.211048 0.929400 -0.302779 -0.211048 0.929400 -0.302779 -0.211048 0.929400 -0.302779 -0.207481 0.926773 -0.313120 -0.207481 0.926773 -0.313120 -0.207481 0.926773 -0.313120 -0.217175 0.970455 -0.105127 -0.217175 0.970455 -0.105127 -0.217175 0.970455 -0.105127 -0.216090 0.970684 -0.105248 -0.216090 0.970684 -0.105248 -0.216090 0.970684 -0.105248 -0.194187 0.000000 -0.980965 -0.194187 0.000000 -0.980965 -0.194187 0.000000 -0.980965 -0.194186 -0.000000 -0.980965 -0.194186 -0.000000 -0.980965 -0.194186 -0.000000 -0.980965 -0.216066 -0.970705 -0.105102 -0.216066 -0.970705 -0.105102 -0.216066 -0.970705 -0.105102 -0.217172 -0.970440 -0.105272 -0.217172 -0.970440 -0.105272 -0.217172 -0.970440 -0.105272 -0.208395 -0.930879 -0.300060 -0.208395 -0.930879 -0.300060 -0.208395 -0.930879 -0.300060 -0.210116 -0.925295 -0.315722 -0.210116 -0.925295 -0.315722 -0.210116 -0.925295 -0.315722 -0.156370 0.985741 -0.062154 -0.000000 0.998433 -0.055963 -0.000000 0.998433 -0.055963 -0.000000 0.998433 -0.055963 -0.159865 0.985177 -0.062205 -0.156370 0.985741 -0.062154 -0.160185 0.987087 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.160185 0.987087 0.000000 -0.160185 0.987087 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.000000 1.000000 0.000000 -0.127993 0.011020 0.991714 -0.139053 -0.000000 0.990285 -0.139053 -0.000000 0.990285 -0.139053 -0.000000 0.990285 -0.113787 0.025124 0.993187 -0.127993 0.011020 0.991714 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.999067 0.000000 -0.043188 -0.999067 0.000000 -0.043189 -0.999054 0.000000 -0.043479 -0.999067 0.000000 -0.043188 -0.999054 0.000000 -0.043479 -0.999054 -0.000000 -0.043483 -0.999067 0.000000 -0.043188 -0.999054 -0.000000 -0.043483 -0.999054 0.000000 -0.043479 -0.999067 0.000000 -0.043188 -0.999054 0.000000 -0.043479 -0.985763 0.159892 -0.052024 -0.999067 0.000000 -0.043188 -0.985763 0.159892 -0.052024 -0.984968 0.164783 -0.051813 -0.194282 0.000000 -0.980946 -0.194282 0.000000 -0.980946 -0.194282 0.000000 -0.980946 -0.194281 -0.000000 -0.980946 -0.194281 -0.000000 -0.980946 -0.194281 -0.000000 -0.980946 --0.000000 0.964133 0.265420 --0.000000 0.964133 0.265419 -0.130684 0.945774 0.297376 -0.130684 0.945774 0.297376 -0.172667 0.936050 0.306588 --0.000000 0.964133 0.265420 -0.130684 0.945774 0.297376 --0.000000 0.964133 0.265419 -0.000000 0.964133 0.265419 -0.000000 0.964133 0.265419 -0.000000 0.964133 0.265419 -0.130684 0.945774 0.297376 -0.000000 0.964133 0.265420 -0.000000 0.964133 0.265419 -0.000000 0.964133 0.265419 -0.000000 0.964133 0.265419 -0.000000 0.964133 0.265420 -0.000000 0.964133 0.265420 -0.000000 0.090945 0.995856 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.090945 0.995856 -0.000000 0.090945 0.995856 --0.974308 0.000000 -0.225220 --0.974308 0.000000 -0.225220 --0.974308 0.000000 -0.225220 --0.974308 0.000000 -0.225220 --0.974308 0.000000 -0.225220 --0.974308 0.000000 -0.225220 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.705510 0.705201 -0.070341 -0.703604 0.707132 -0.070049 -0.984968 0.164783 -0.051813 -0.984968 0.164783 -0.051813 -0.985763 0.159892 -0.052024 -0.705510 0.705201 -0.070341 -0.707109 0.707105 0.000000 -0.707109 0.707105 0.000000 -0.160185 0.987087 0.000000 -0.160185 0.987087 0.000000 -0.160185 0.987087 0.000000 -0.707109 0.707105 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.068966 0.069266 0.995211 -0.069489 0.068754 0.995211 -0.127993 0.011020 0.991714 -0.127993 0.011020 0.991714 -0.113787 0.025124 0.993187 -0.068966 0.069266 0.995211 -0.656527 0.658833 0.367303 -0.658523 0.656830 0.367316 -0.172667 0.936050 0.306588 -0.172667 0.936050 0.306588 -0.130684 0.945774 0.297376 -0.656527 0.658833 0.367303 -0.393996 0.394840 -0.829981 -0.395300 0.393548 -0.829975 -0.067299 0.649221 -0.757617 -0.067299 0.649221 -0.757617 -0.128272 0.611135 -0.781063 -0.393996 0.394840 -0.829981 -0.707076 0.703599 -0.070651 -0.705510 0.705201 -0.070341 -0.985763 0.159892 -0.052024 -0.985763 0.159892 -0.052024 -0.986520 0.155080 -0.052242 -0.707076 0.703599 -0.070651 -0.159865 0.985177 -0.062205 -0.163218 0.984625 -0.062245 -0.703604 0.707132 -0.070049 -0.703604 0.707132 -0.070049 -0.705510 0.705201 -0.070341 -0.159865 0.985177 -0.062205 -0.987087 0.160182 0.000000 -0.987087 0.160182 0.000000 -0.707109 0.707105 0.000000 -0.707109 0.707105 0.000000 -0.707109 0.707105 0.000000 -0.987087 0.160182 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.024597 0.112430 0.993355 -0.011116 0.125442 0.992039 -0.069489 0.068754 0.995211 -0.069489 0.068754 0.995211 -0.068966 0.069266 0.995211 -0.024597 0.112430 0.993355 -0.943771 0.131276 0.303418 -0.934506 0.171549 0.311880 -0.658523 0.656830 0.367316 -0.658523 0.656830 0.367316 -0.656527 0.658833 0.367303 -0.943771 0.131276 0.303418 -0.613770 0.129389 -0.778810 -0.653290 0.067038 -0.754134 -0.395300 0.393548 -0.829975 -0.395300 0.393548 -0.829975 -0.393996 0.394840 -0.829981 -0.613770 0.129389 -0.778810 -0.156370 0.985741 -0.062154 -0.159865 0.985177 -0.062205 -0.705510 0.705201 -0.070341 -0.705510 0.705201 -0.070341 -0.707076 0.703599 -0.070651 -0.156370 0.985741 -0.062154 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -0.999042 0.000000 -0.043762 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -0.987088 -0.160179 0.000000 -0.987088 -0.160179 0.000000 -0.987088 -0.160179 0.000000 -1.000000 -0.000000 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 -0.090945 0.995856 -0.000000 -0.136135 0.990690 -0.000000 -0.136135 0.990690 -0.000000 -0.090945 0.995856 -0.000000 -0.090945 0.995856 -0.000000 -0.136135 0.990690 -0.011116 -0.125442 0.992039 -0.000000 -0.090945 0.995856 -0.000000 -0.136135 0.990690 -0.011116 -0.125442 0.992039 -0.000000 -0.136135 0.990690 -0.024596 -0.112431 0.993355 -0.962160 -0.000000 0.272486 -0.962160 0.000000 0.272486 -0.943771 -0.131278 0.303418 -0.943771 -0.131278 0.303418 -0.934506 -0.171549 0.311879 -0.962160 -0.000000 0.272486 -0.067300 -0.649221 -0.757617 -0.128272 -0.611136 -0.781063 -0.000000 -0.686714 -0.726928 -0.000000 -0.686714 -0.726928 -0.000000 -0.686714 -0.726928 -0.067300 -0.649221 -0.757617 -0.163219 -0.984624 -0.062245 -0.000000 -0.998433 -0.055964 --0.000000 -0.998433 -0.055963 --0.000000 -0.998433 -0.055963 -0.159865 -0.985177 -0.062205 -0.163219 -0.984624 -0.062245 -0.999054 0.000000 -0.043479 -0.985762 -0.159895 -0.052024 -0.986519 -0.155083 -0.052243 -0.986519 -0.155083 -0.052243 -0.999027 0.000000 -0.044102 -0.999054 0.000000 -0.043479 -0.999038 0.000000 -0.043860 -0.999038 0.000000 -0.043860 -0.999038 0.000000 -0.043860 -0.999038 0.000000 -0.043860 -0.999038 0.000000 -0.043860 -0.999038 0.000000 -0.043860 -0.999054 -0.000000 -0.043479 -0.999054 0.000000 -0.043483 -0.999027 -0.000000 -0.044102 -0.999027 -0.000000 -0.044102 -0.999027 0.000000 -0.044102 -0.999054 -0.000000 -0.043479 -0.691125 -0.000000 -0.722735 -0.613769 -0.129389 -0.778811 -0.653289 -0.067036 -0.754135 -0.653289 -0.067036 -0.754135 -0.691125 -0.000000 -0.722735 -0.691125 -0.000000 -0.722735 -0.682748 0.000000 -0.730654 -0.682748 0.000000 -0.730654 -0.682748 0.000000 -0.730654 -0.682748 0.000000 -0.730654 -0.682748 0.000000 -0.730654 -0.682748 0.000000 -0.730654 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.691125 0.000000 -0.722735 -0.217362 0.970528 -0.104062 -0.217362 0.970528 -0.104062 -0.217362 0.970528 -0.104062 -0.216100 0.970831 -0.103869 -0.216100 0.970831 -0.103869 -0.216100 0.970831 -0.103869 -0.205507 0.932071 -0.298347 -0.205506 0.932071 -0.298347 -0.205507 0.932071 -0.298347 -0.207347 0.926207 -0.314876 -0.207347 0.926207 -0.314876 -0.207347 0.926207 -0.314876 -0.207481 -0.926773 -0.313119 -0.207481 -0.926773 -0.313119 -0.207481 -0.926773 -0.313119 -0.211048 -0.929400 -0.302779 -0.211048 -0.929400 -0.302779 -0.211048 -0.929400 -0.302779 -0.216091 -0.970684 -0.105248 -0.216090 -0.970684 -0.105248 -0.216090 -0.970684 -0.105248 -0.217175 -0.970455 -0.105127 -0.217175 -0.970455 -0.105127 -0.217175 -0.970455 -0.105127 -0.194186 0.000000 -0.980965 -0.194186 0.000000 -0.980965 -0.194186 0.000000 -0.980965 -0.194187 0.000000 -0.980965 -0.194187 0.000000 -0.980965 -0.194187 0.000000 -0.980965 -0.217172 0.970440 -0.105272 -0.217172 0.970440 -0.105272 -0.217171 0.970440 -0.105272 -0.216066 0.970705 -0.105103 -0.216066 0.970705 -0.105102 -0.216066 0.970705 -0.105103 -0.210116 0.925296 -0.315720 -0.210116 0.925296 -0.315720 -0.210116 0.925296 -0.315720 -0.208395 0.930880 -0.300057 -0.208395 0.930880 -0.300057 -0.208395 0.930880 -0.300057 -0.156370 -0.985741 -0.062154 -0.159865 -0.985177 -0.062205 --0.000000 -0.998433 -0.055963 --0.000000 -0.998433 -0.055963 -0.000000 -0.998433 -0.055963 -0.156370 -0.985741 -0.062154 -0.160183 -0.987087 0.000000 -0.160183 -0.987087 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.160183 -0.987087 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.000000 -1.000000 0.000000 -0.127993 -0.011020 0.991714 -0.113788 -0.025124 0.993187 -0.139053 -0.000000 0.990285 -0.139053 -0.000000 0.990285 -0.139053 -0.000000 0.990285 -0.127993 -0.011020 0.991714 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.683002 0.000000 -0.730417 -0.999067 0.000000 -0.043188 -0.984968 -0.164786 -0.051813 -0.985762 -0.159895 -0.052024 -0.999067 0.000000 -0.043188 -0.985762 -0.159895 -0.052024 -0.999054 0.000000 -0.043479 -0.999067 0.000000 -0.043188 -0.999054 0.000000 -0.043479 -0.999054 0.000000 -0.043483 -0.999067 0.000000 -0.043188 -0.999054 0.000000 -0.043483 -0.999054 -0.000000 -0.043479 -0.999067 0.000000 -0.043188 -0.999054 -0.000000 -0.043479 -0.999067 0.000000 -0.043189 -0.194281 0.000000 -0.980946 -0.194281 0.000000 -0.980946 -0.194281 0.000000 -0.980946 -0.194282 0.000000 -0.980946 -0.194282 0.000000 -0.980946 -0.194282 0.000000 -0.980946 --0.000000 -0.964133 0.265420 -0.172668 -0.936050 0.306589 -0.130685 -0.945774 0.297376 -0.130685 -0.945774 0.297376 --0.000000 -0.964133 0.265419 --0.000000 -0.964133 0.265420 -0.130685 -0.945774 0.297376 -0.000000 -0.964133 0.265419 -0.000000 -0.964133 0.265419 -0.000000 -0.964133 0.265419 --0.000000 -0.964133 0.265419 -0.130685 -0.945774 0.297376 -0.000000 -0.964133 0.265420 -0.000000 -0.964133 0.265420 -0.000000 -0.964133 0.265419 -0.000000 -0.964133 0.265419 -0.000000 -0.964133 0.265419 -0.000000 -0.964133 0.265420 -0.000000 -0.090945 0.995856 -0.000000 -0.090945 0.995856 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 0.000000 1.000000 -0.000000 -0.090945 0.995856 --0.974308 0.000000 -0.225219 --0.974308 0.000000 -0.225219 --0.974308 0.000000 -0.225219 --0.974308 0.000000 -0.225219 --0.974308 0.000000 -0.225219 --0.974308 0.000000 -0.225219 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.975766 0.000000 -0.218815 -0.705508 -0.705203 -0.070341 -0.985762 -0.159895 -0.052024 -0.984968 -0.164786 -0.051813 -0.984968 -0.164786 -0.051813 -0.703602 -0.707133 -0.070050 -0.705508 -0.705203 -0.070341 -0.707109 -0.707104 0.000000 -0.160183 -0.987087 0.000000 -0.160183 -0.987087 0.000000 -0.160183 -0.987087 0.000000 -0.707109 -0.707104 0.000000 -0.707109 -0.707104 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.068966 -0.069266 0.995212 -0.113788 -0.025124 0.993187 -0.127993 -0.011020 0.991714 -0.127993 -0.011020 0.991714 -0.069489 -0.068753 0.995211 -0.068966 -0.069266 0.995212 -0.656525 -0.658835 0.367303 -0.130685 -0.945774 0.297376 -0.172668 -0.936050 0.306589 -0.172668 -0.936050 0.306589 -0.658524 -0.656830 0.367316 -0.656525 -0.658835 0.367303 -0.393995 -0.394842 -0.829980 -0.128272 -0.611136 -0.781063 -0.067300 -0.649221 -0.757617 -0.067300 -0.649221 -0.757617 -0.395300 -0.393547 -0.829975 -0.393995 -0.394842 -0.829980 -0.707074 -0.703601 -0.070651 -0.986519 -0.155083 -0.052243 -0.985762 -0.159895 -0.052024 -0.985762 -0.159895 -0.052024 -0.705508 -0.705203 -0.070341 -0.707074 -0.703601 -0.070651 -0.159865 -0.985177 -0.062205 -0.705508 -0.705203 -0.070341 -0.703602 -0.707133 -0.070050 -0.703602 -0.707133 -0.070050 -0.163219 -0.984624 -0.062245 -0.159865 -0.985177 -0.062205 -0.987088 -0.160179 0.000000 -0.707109 -0.707104 0.000000 -0.707109 -0.707104 0.000000 -0.707109 -0.707104 0.000000 -0.987088 -0.160179 0.000000 -0.987088 -0.160179 0.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.000000 0.000000 -1.000000 -0.024596 -0.112431 0.993355 -0.068966 -0.069266 0.995212 -0.069489 -0.068753 0.995211 -0.069489 -0.068753 0.995211 -0.011116 -0.125442 0.992039 -0.024596 -0.112431 0.993355 -0.943771 -0.131278 0.303418 -0.656525 -0.658835 0.367303 -0.658524 -0.656830 0.367316 -0.658524 -0.656830 0.367316 -0.934506 -0.171549 0.311879 -0.943771 -0.131278 0.303418 -0.613769 -0.129389 -0.778811 -0.393995 -0.394842 -0.829980 -0.395300 -0.393547 -0.829975 -0.395300 -0.393547 -0.829975 -0.653289 -0.067036 -0.754135 -0.613769 -0.129389 -0.778811 -0.156370 -0.985741 -0.062154 -0.707074 -0.703601 -0.070651 -0.705508 -0.705203 -0.070341 -0.705508 -0.705203 -0.070341 -0.159865 -0.985177 -0.062205 -0.156370 -0.985741 -0.062154 - + + 0 0.9870878 -0.1601809 0 1 0 0 1 0 0 1 0 0 0.986432 -0.1641704 0 0.7071088 -0.7071049 0 0.7013249 -0.7128418 2.58318e-7 -1 0 2.64254e-7 -1 3.06372e-6 2.58318e-7 -1 -6.38884e-7 -0.9870879 0 -0.16018 -1 0 0 -1 2.71718e-7 0 -1 6.7268e-7 0 -0.9861714 0 -0.1657289 0 -0.9996106 -0.02790832 -9.08455e-7 -0.9984422 -0.05579531 1.19549e-6 -0.9984422 -0.05579572 0 -0.6868233 -0.7268245 0 -0.6868219 -0.7268257 0 -0.6868216 -0.7268261 -0.9863993 -0.1625567 -0.02432835 -1 0 5.83388e-7 -0.9997988 0 -0.02006208 -4.22359e-6 -0.1601835 0.9870873 0 0.1601836 0.9870873 -6.07714e-6 -0.1601834 0.9870874 0 0 1 -3.01884e-7 -1 0 0 -1 0 0 -0.9870877 -0.1601811 -7.64499e-7 -1 0 0 -0.9864322 -0.1641693 1 0 0 0.9870873 0 -0.160184 0.986172 0 -0.1657259 -1 0 8.83725e-7 -0.9997988 0 -0.02006196 -0.9997988 0 -0.02006196 0 -1 -6.08475e-7 0 -1 0 0 -1 0 0 -1 -2.62574e-7 6.58836e-7 1 -3.61968e-7 1.37451e-6 1 -3.47637e-6 2.27575e-7 1 1.85833e-6 3.6743e-7 1 1.0503e-6 -0.9873961 0 0.1582689 -0.7098549 0 0.7043481 -0.7098619 0 0.7043409 -0.9870876 -0.1601823 4.33979e-7 -0.7056326 -0.7077815 -0.03358781 -0.7071077 -0.7071059 4.13474e-7 -1 5.07671e-7 0 -1 4.34535e-7 -2.26119e-7 -1 2.29902e-7 0 -0.9870875 1.06397e-6 0.1601827 1 -1.43892e-7 0 1 -8.69075e-7 0 1 -1.41894e-7 0 0.9870873 0 0.1601834 -1.62216e-6 0 1 4.04197e-7 0 1 -1.62216e-6 0 1 -8.43153e-6 0 1 3.85477e-7 0 1 -0.7055894 -0.7053751 -0.06774622 6.23115e-7 0 1 -1 2.53423e-7 -5.8239e-7 -1 1.44541e-7 6.7306e-7 -1 1.61521e-7 1.36213e-7 -1 1.81823e-7 -1.42236e-7 -1 1.28363e-7 -5.82434e-7 -1 2.89053e-7 6.7299e-7 -1 1.85309e-7 1.41806e-7 -1 1.57936e-7 -1.36638e-7 -2.7322e-7 -1 -1.28169e-6 -3.27087e-7 -1 1.01145e-5 -2.68087e-7 -1 -2.81754e-6 -2.72648e-7 -1 2.99858e-6 2.66225e-7 -1 -7.05927e-6 -3.27087e-7 -1 -1.01145e-5 1.81969e-7 -1 -2.33425e-6 2.72648e-7 -1 5.38468e-6 0.278629 -0.944534 0.1738432 0.2048742 -0.9315165 0.3005057 -0.1212346 -0.9439502 -0.3070185 -0.1997055 -0.9568911 -0.2108962 -0.2936673 -0.950362 -0.1028178 0.437375 -0.8984282 0.03911775 -0.6827594 0 0.7306434 -0.1399397 0 0.9901601 -0.6827578 -2.19769e-7 0.7306448 0.4467667 0 -0.8946505 0.1652552 0 -0.9862508 0.1652569 0 -0.9862506 -0.9725064 0 -0.2328764 -0.6614934 0 -0.749951 -0.6614956 0 -0.7499491 -0.03823196 0 -0.999269 -0.1652568 0 -0.9862506 -0.03822946 0 -0.9992691 -0.7592793 -0.6262857 -0.1768087 -0.4373747 -0.8984282 0.03911715 -0.5964136 -0.7752248 0.2081282 0.4667751 -0.877353 -0.1112343 -0.3784908 -0.9224358 0.07653093 0.265752 -0.7562036 -0.59794 0.1997058 -0.956891 -0.2108964 0.4900572 -0.7793552 -0.3904479 0.5964142 -0.7752245 0.2081278 0.2145828 -0.8739152 -0.4361498 -0.08415716 -0.883121 -0.4615353 0 -0.6316557 -0.7752492 0 -0.9029365 -0.4297743 0.01676148 -0.961573 0.2740374 0 -0.4824078 0.8759468 0 -0.9605016 0.2782745 0 -1 2.64534e-6 1.56916e-5 -0.4801356 -0.8771944 0 -0.9999967 -0.002593994 0.7248033 -0.6816616 -0.09998887 0.3784909 -0.9224357 0.07653123 0.7664357 -0.6282345 0.1337828 -0.05820691 -0.9347167 -0.3505949 0 -1 2.0448e-6 0 -0.9285686 -0.371161 0.1212345 -0.9439498 -0.3070198 -0.2048748 -0.9315175 0.3005021 -0.278629 -0.944534 0.1738433 0.2936673 -0.9503622 -0.1028173 0.1399397 0 0.9901601 0.68276 0 0.7306428 0.6827576 -4.39539e-7 0.730645 0 0 -1 0.1744615 0 -0.9846641 0 0 -1 0 0 1 0.1399398 0 0.9901601 0 -0.4824088 0.8759463 0 -0.4824078 0.8759468 -0.9659468 0 0.2587407 -0.9725063 0 -0.2328768 0.6614933 0 -0.7499511 0.9725064 0 -0.2328763 0.6614953 0 -0.7499494 -0.466775 -0.877353 -0.1112335 -0.7248033 -0.6816615 -0.09998899 -0.2145866 -0.8739122 -0.4361538 -0.01676166 -0.9615732 0.2740367 0 -0.9999967 -0.002593874 0 -1 2.25307e-6 -1.64872e-5 -0.4801349 -0.8771947 -0.7055888 -0.7053757 -0.06774663 -0.1598314 -0.9852283 -0.06147646 -0.1074706 -0.7218201 0.6836855 -0.2137202 -0.2137196 0.9532301 -0.5374585 -0.5374583 0.6498285 -0.4566125 -0.4538647 -0.7651875 -0.6756023 -0.1117634 -0.7287458 -0.6764718 -0.1071247 -0.7286359 0.6990305 0 -0.715092 0.1601736 0 -0.9870889 0.1592839 0 -0.9872329 -0.1557462 -0.9754873 0.1554598 0 -1 -3.66334e-6 0 -0.9873964 0.1582666 -0.1601737 0 -0.9870889 -0.7071094 7.34059e-7 0.7071043 -0.9870873 3.54703e-7 0.1601838 -0.7071097 0 0.7071039 -0.3199501 0 0.9474344 0.9870874 0 0.160183 -0.999195 0 -0.04011702 0.7071093 0 0.7071043 -1 0 4.2077e-7 -1 0 4.9274e-7 -1 0 5.43204e-7 0 -0.9996106 -0.02790844 0 -1 0 0 -1 -2.46079e-6 0 -1 2.39763e-7 0 -0.9996106 -0.02790808 -0.9991952 -1.74618e-7 -0.04011255 -0.9991958 4.92441e-7 -0.04009848 -0.999196 -4.30279e-6 -0.040093 0 -1 -2.4496e-6 0 -1 -3.96395e-7 0.9848546 -8.98659e-7 0.1733827 0.9739219 -1.35578e-7 -0.2268836 0.9739232 0 -0.2268784 0.7661257 0 -0.6426908 0.4467697 0 -0.894649 0.984855 -6.34976e-7 0.1733803 -0.3348196 -0.8625778 -0.379283 -0.5132887 -0.6309189 -0.5817869 0.05820697 -0.9347171 -0.3505938 0 -0.4824081 0.8759467 0 -0.4824079 0.8759468 -0.4467697 0 -0.894649 -0.766125 0 -0.6426916 -0.4467667 0 -0.8946505 0.9725065 0 -0.232876 0.9659467 0 0.2587413 -0.1652551 0 -0.9862509 -0.1744604 0 -0.9846642 -0.7077748 -0.7031856 -0.06771242 -0.9859344 -0.1599349 -0.04852175 -0.9867233 -0.1550676 -0.04828184 -0.6987367 -0.6987364 0.1534098 -0.1601814 -0.9870876 2.94412e-7 -0.7218201 -0.1074703 0.6836856 -0.9754872 -0.1557455 0.1554611 1.42234e-6 0.9870871 0.1601845 -0.1102728 -0.6713885 -0.7328557 -0.107384 -0.6719025 -0.7328135 -0.6922404 0 -0.7216671 0 -0.3199425 0.9474371 0 -0.7098583 0.7043446 0 -0.3199415 0.9474374 0 -0.7071087 -0.707105 0 -0.7013257 -0.712841 0 -0.1601837 -0.9870873 0 -0.1595335 -0.9871925 -0.7071004 0 -0.7071132 -0.699027 0 -0.7150954 -0.1592828 0 -0.987233 -0.3147554 -0.03424978 0.9485547 -0.7098534 0 0.7043495 0 -0.7071085 0.7071051 0 -0.9870875 0.1601827 0 -0.9870879 0.1601803 -0.6922457 0 -0.7216619 -0.6922406 0 -0.7216669 -0.6922469 0 -0.7216608 1.44105e-7 0.7071087 0.7071049 1.60712e-6 0.7071068 0.7071068 0.7070983 0 -0.7071154 0.7071012 0 0.7071124 0.1601842 0 0.9870873 -0.1601867 0 0.9870867 -0.999195 -6.06873e-7 -0.04011785 0 -0.9996105 -0.02790832 0 -1 -2.01709e-7 -2.20479e-7 -1 1.35399e-6 -2.58316e-7 -1 -2.30979e-6 -0.9997988 1.18688e-6 -0.02006363 -1 0 5.83845e-7 -1.45202e-6 -0.7071073 0.7071063 0 0.1601839 -0.9870873 0 -0.9873963 0.158268 0 -0.7098578 0.7043452 -0.9997987 0 -0.02006208 -0.999195 -2.22531e-7 -0.04011702 -0.7071072 -0.7071065 5.25018e-7 -0.1601818 -0.9870876 3.09972e-7 -0.1616261 -0.9863744 -0.03070288 -0.9859344 -0.1599349 -0.04852157 -0.9991951 0 -0.04011607 -0.1598315 -0.9852282 -0.0614773 -0.1567754 -0.9857252 -0.06137925 -3.20695e-7 -0.9984423 -0.05579394 0 -0.9984423 -0.05579572 -2.90922e-6 -0.9984422 -0.05579519 -1.70379e-6 -0.9996106 -0.02790665 -3.10814e-6 -0.9984417 -0.05580544 -2.28733e-6 -0.998442 -0.05579948 2.194e-6 -0.9984413 -0.05581086 2.53638e-7 -0.9984423 -0.05579525 0 -0.9984422 -0.05579513 0 -1 -1.55229e-6 -1 1.54676e-7 0 -1 1.71284e-7 -1.33787e-7 -1 2.12911e-7 -1.33787e-7 -0.999195 2.01332e-6 -0.04011696 -1 1.34244e-7 0 -0.2190476 -0.944662 0.2441967 0.08415734 -0.8831214 -0.4615345 0.334819 -0.8625779 -0.3792829 -0.05801951 -0.9170412 0.3945493 -0.9739217 -1.35578e-7 -0.2268846 -0.9848547 -6.50103e-7 0.1733822 -0.9739229 0 -0.2268792 -0.9848549 -5.85297e-7 0.1733808 0.1744579 0 -0.9846646 -0.1157195 -0.7098081 -0.6948248 -0.5178269 -0.6479333 0.5586034 -0.1291518 -0.623757 -0.7708742 -0.2657518 -0.7562035 -0.5979401 -0.1136557 -0.626016 0.7714833 0 -0.9033942 0.4288111 0.11572 -0.70981 -0.6948227 -0.4900569 -0.7793547 -0.3904494 0.05801969 -0.9170417 0.3945482 -0.1399398 0 0.9901601 1.12883e-5 0 -1 0.8661082 0 0.4998565 0.8661106 0 0.4998523 0 -0.7124643 -0.7017084 0.5178266 -0.6479339 0.5586029 0.1291515 -0.6237556 -0.7708753 0.1136562 -0.6260171 0.7714823 0 -0.6322342 0.7747774 0 -0.7098587 0.7043442 -0.03424966 -0.3147612 0.9485529 0 0.1595337 -0.9871926 -0.9870874 -0.1601827 6.11188e-7 0 -0.686823 -0.7268247 -0.9873963 0 0.1582678 -1 0 4.92738e-7 0.1601733 0 0.987089 -1 1.58453e-7 0 -1 2.09567e-7 0 -1 2.70051e-7 0 -1 0 8.84311e-7 5.45731e-7 0.9870876 0.1601817 -0.999195 0 -0.04011702 -1 1.50163e-7 0 0.2190478 -0.944662 0.2441961 -0.7661256 0 -0.642691 0.7661262 0 -0.6426903 -0.8661087 0 0.4998558 -0.9659469 0 0.2587408 0.759279 -0.6262858 -0.1768093 0.03823196 0 -0.9992689 0.03822946 0 -0.9992691 -0.1744571 0 -0.9846648 -1.12883e-5 0 -1 0 0 -1 0 0.9870877 -0.160181 0 1 0 0 1 0 0 1 0 0 0.7071088 -0.7071048 -2.58318e-7 -1 0 -2.58318e-7 -1 0 -2.64254e-7 -1 3.10822e-6 0.9870879 0 -0.1601797 1 2.39111e-7 0 1 5.91958e-7 0 0.9861715 0 -0.1657284 0 -0.9996106 -0.02790832 9.08456e-7 -0.9984422 -0.05579525 0 -0.9996106 -0.02790862 0 -0.6868206 -0.726827 0 -0.6868247 -0.7268232 0 -0.6868193 -0.7268282 0.9863992 -0.1625571 -0.02432841 1 -2.21695e-7 5.83388e-7 0.9870876 -0.1601821 3.74961e-7 0 0.1601837 0.9870873 2.91576e-6 -0.1601836 0.9870873 4.58619e-6 -0.1601831 0.9870874 3.01884e-7 -1 0 0 -0.9870877 -0.1601809 0 -1 0 7.645e-7 -1 0 0 -0.9864322 -0.1641693 -0.9870871 0 -0.1601846 -0.9861717 0 -0.1657267 1 -3.38551e-7 8.83725e-7 0.9997988 0 -0.02006214 1 0 8.84311e-7 0 -1 0 -6.58833e-7 1 -2.44686e-7 -2.27572e-7 1 -5.75571e-7 -1.37449e-6 1 -3.47633e-6 -3.6743e-7 1 0 0.7098549 0 0.7043481 0.9873961 0 0.1582689 0.7098619 0 0.7043409 0.7056325 -0.7077816 -0.03358793 0.7071084 -0.7071052 2.88078e-7 1 8.7345e-7 0 1 2.18195e-7 0 1 0 -4.52238e-7 0.9870875 9.46284e-7 0.1601822 -1 2.61068e-7 0 -1 -1.17929e-6 0 -1 3.4763e-6 0 -0.9870873 -2.38802e-7 0.160184 1.62215e-6 0 1 -4.04197e-7 0 1 8.43149e-6 0 1 -3.85477e-7 0 1 0.7055897 -0.7053749 -0.06774628 0.9859344 -0.1599347 -0.04852157 -6.23115e-7 0 1 1 0 -5.8239e-7 1 3.09113e-7 1.36214e-7 1 2.89083e-7 6.7306e-7 1 0 -1.42236e-7 1 0 -5.82434e-7 1 6.18689e-7 1.41806e-7 1 2.89053e-7 6.7299e-7 1 0 -1.36638e-7 2.7322e-7 -1 2.83455e-6 2.68087e-7 -1 5.33281e-7 3.27087e-7 -1 5.05724e-6 2.72648e-7 -1 -3.59508e-6 -2.66225e-7 -1 -1.25295e-5 -1.93693e-7 -1 6.01096e-6 3.27087e-7 -1 -1.68575e-6 -2.60924e-7 -1 -1.47351e-6 -0.2786288 -0.9445343 0.1738423 0.1212345 -0.9439499 -0.3070192 -0.2048746 -0.9315175 0.3005025 0.1997056 -0.9568908 -0.2108973 -0.4373745 -0.8984284 0.03911739 0.2936668 -0.9503622 -0.1028176 0.1399402 0 0.99016 0.6827595 0 0.7306433 0.682758 -1.75815e-6 0.7306446 -0.1652553 0 -0.9862509 -0.4467671 0 -0.8946504 0.6614949 0 -0.7499498 0.1652568 0 -0.9862506 0.03823196 0 -0.999269 0.7592791 -0.6262861 -0.1768085 0.4373746 -0.8984283 0.03911787 0.4667747 -0.8773532 -0.1112331 -0.4667757 -0.8773525 -0.111234 -0.265752 -0.756204 -0.5979394 -0.199706 -0.9568906 -0.2108983 -0.1212347 -0.9439499 -0.3070192 -0.5964138 -0.7752249 0.2081277 -0.2145825 -0.8739183 -0.4361435 0 -0.6316536 -0.7752509 0.08415788 -0.8831222 -0.4615331 0 -0.9029361 -0.4297748 -0.01676154 -0.9615732 0.2740367 0 -0.4824069 0.8759473 0 -0.4824092 0.8759461 0 -1 2.7761e-6 -1.56916e-5 -0.4801366 -0.8771939 0 -0.9999967 -0.002596437 -0.7248024 -0.6816624 -0.09998863 -0.3784905 -0.9224357 0.07653319 -0.2936671 -0.9503621 -0.1028186 0.05820685 -0.9347169 -0.3505941 0 -1 2.52521e-6 0.2786283 -0.9445343 0.1738424 0.2048748 -0.9315175 0.3005024 -0.6827595 0 0.7306433 -0.1399402 0 0.99016 -0.6827578 0 0.7306448 -0.1744604 0 -0.9846643 0 0 -1 0 -0.4824104 0.8759453 0.9659468 0 0.2587407 -0.9725064 0 -0.2328763 -0.6614942 0 -0.7499504 -0.6614954 0 -0.7499492 0.7248013 -0.6816637 -0.09998881 0.3784903 -0.9224359 0.07653313 0.7664355 -0.6282341 0.1337859 0.5964125 -0.7752259 0.2081276 0.2145859 -0.873916 -0.4361467 0.01676166 -0.9615732 0.2740367 0 -1 2.64534e-6 1.64872e-5 -0.480136 -0.8771941 0.7055885 -0.705376 -0.06774663 0.1598314 -0.9852283 -0.0614764 0.1598315 -0.9852282 -0.0614773 0.1074706 -0.7218199 0.6836857 0.2137191 -0.2137196 0.9532303 0.03424966 -0.3147604 0.9485531 0.4566127 -0.4538648 -0.7651873 0.6756019 -0.1117635 -0.7287462 0.4545233 -0.4559328 -0.7652018 -0.6990299 0 -0.7150925 -0.160174 0 -0.9870889 -0.7070981 0 -0.7071155 0 -1 0 0.1557461 -0.9754874 0.1554599 -0.1592839 0 -0.9872329 0.1601736 0 -0.9870889 0.7071096 6.11522e-7 0.707104 0.9870873 2.8474e-7 0.1601837 0.3199501 0 0.9474344 -0.9870873 0 0.1601838 0.999195 0 -0.0401172 0.999195 0 -0.04011726 -0.707109 0 0.7071046 1 0 4.2077e-7 1 0 4.9274e-7 1 0 5.83845e-7 0 -1 -5.83258e-7 0 -0.9996106 -0.02790856 0 -1 0 0 -0.9996105 -0.02790844 0 -1 0 0 -1 0 -1.19549e-6 -0.9984422 -0.05579507 2.92896e-6 -0.9984423 -0.05579513 0.9991958 2.05138e-7 -0.04009848 0.9991952 -6.00025e-7 -0.04011243 0.9991959 -5.7239e-6 -0.040093 -0.9739217 0 -0.2268847 -0.9848545 0 0.1733831 -0.9739229 0 -0.2268794 -0.4467703 0 -0.8946488 -0.766125 0 -0.6426916 -0.9848549 0 0.173381 0.3348194 -0.8625776 -0.3792834 -0.05820691 -0.9347169 -0.3505941 0.766125 0 -0.6426916 0.4467703 0 -0.8946488 0.4467671 0 -0.8946504 -0.9659468 0 0.2587412 -0.9725065 0 -0.232876 0.1652554 0 -0.9862509 0.1744604 0 -0.9846642 0.7077753 -0.703185 -0.06771254 0.9859343 -0.1599354 -0.04852175 0.1601815 -0.9870876 0 0.6987365 -0.6987366 0.1534094 0.721819 -0.1074717 0.6836866 0.537459 -0.5374579 0.6498283 0.9754872 -0.1557461 0.155461 -1.42234e-6 0.9870874 0.1601831 -5.45732e-7 0.9870874 0.1601834 0.1102726 -0.6713868 -0.7328572 0.6922404 0 -0.7216671 0.6764709 -0.1071243 -0.7286368 0.6922408 0 -0.7216666 0 -0.319941 0.9474376 0 -0.7098588 0.7043441 0 -0.7098582 0.7043446 0 -0.7071088 -0.7071048 0 -0.7013258 -0.7128409 0 -0.1601837 -0.9870873 0.7071006 0 -0.707113 0.6990272 0 -0.7150951 0.3147523 -0.03425014 0.9485557 0.7098534 0 0.7043496 0.3199265 0 0.9474424 -2.2454e-7 -0.9870874 0.1601828 0 -0.7071088 0.7071049 0 -0.9870879 0.1601802 0.6922406 0 -0.7216668 0.6922459 0 -0.7216617 0.6922472 0 -0.7216605 -1.44105e-7 0.7071074 0.7071062 0 0.1601837 0.9870873 -0.1601844 0 0.9870872 -0.707101 0 0.7071126 0.1601868 0 0.9870867 0.1601868 0 0.9870868 1 0 5.43204e-7 0.999195 -8.26818e-7 -0.04011785 5.93155e-7 -0.9984424 -0.05579239 2.20479e-7 -1 -1.98976e-6 0 -1 -2.01709e-7 2.58316e-7 -1 0 0.9997988 1.36444e-6 -0.02006363 0.9997988 0 -0.02006214 1.13216e-6 -0.7071071 0.7071066 0 -0.1595335 -0.9871925 0 0.160184 -0.9870873 0 -0.9873965 0.1582665 0.999195 2.50845e-6 -0.0401169 0.9997988 0 -0.02006214 0.999195 0 -0.0401166 0.1601818 -0.9870876 4.55808e-7 0.7071075 -0.7071061 5.23425e-7 0.161626 -0.9863744 -0.03070265 0.9991951 0 -0.04011607 3.20695e-7 -0.9984425 -0.05579006 0.1567753 -0.9857252 -0.06137931 1.72794e-6 -0.9996106 -0.02790695 3.15784e-6 -0.9984418 -0.05580544 2.32463e-6 -0.9984421 -0.05579906 -2.44768e-7 -0.9984422 -0.05579519 -2.15731e-6 -0.9984415 -0.05581074 0 -0.9984422 -0.05579519 1 4.25821e-7 -1.33787e-7 1 2.37204e-7 0 1 4.25821e-7 -1.33787e-7 1 5.23343e-7 0 0.2190478 -0.9446618 0.2441971 -0.08415722 -0.8831217 -0.461534 0.05801975 -0.9170423 0.3945468 0 -0.9033939 0.4288117 0.9848546 -1.98845e-6 0.1733827 0.9739217 0 -0.2268847 0.9739229 0 -0.2268794 0.9848549 -3.97433e-7 0.1733809 -0.1744576 0 -0.9846647 0 -0.9605011 0.278276 0 -0.9285693 -0.3711591 0.1157194 -0.7098091 -0.6948237 0 -0.7124658 -0.7017068 0.5178264 -0.6479319 0.5586056 0.1136567 -0.6260194 0.7714803 0.1291519 -0.6237561 -0.770875 0.2657517 -0.7562035 -0.5979402 0.4900565 -0.779355 -0.3904491 0 -0.6322322 0.774779 -0.1157198 -0.7098087 -0.6948241 -0.05801969 -0.9170425 0.3945465 0.1399398 0 0.9901601 -1.12883e-5 0 -1 -0.8661082 0 0.4998567 -0.5178261 -0.6479327 0.558605 -0.2190482 -0.9446619 0.2441964 -0.1291515 -0.6237546 -0.7708762 -0.3348184 -0.8625783 -0.3792826 -0.5132874 -0.6309198 -0.5817872 -0.490056 -0.7793556 -0.3904483 -0.1136564 -0.6260207 0.7714793 0 -0.3199424 0.9474371 0 0.7013252 -0.7128415 0.9870876 -0.160182 5.45838e-7 0.1073837 -0.6719009 -0.732815 0 -0.6868243 -0.7268236 0 -0.6868253 -0.7268226 0.9873963 0 0.1582678 1 0 4.92738e-7 -0.1601733 0 0.987089 1 2.68704e-7 0 1 0 0 1 2.70051e-7 0 -1.60712e-6 0.7071076 0.7071061 0.9867236 -0.1550667 -0.0482819 1 0 0 0.7661255 0 -0.642691 -0.7661255 0 -0.642691 0.8661087 0 0.4998558 -0.7592794 -0.6262854 -0.1768091 0.1744571 0 -0.9846648 1.12883e-5 0 -1 0 -0.9870877 -0.160181 0 -1 0 0 -1 0 0 -0.9864322 -0.1641694 0 -0.7071088 -0.7071048 2.64254e-7 1 2.57136e-6 2.58318e-7 1 0 2.58318e-7 1 0 -0.9870879 0 -0.16018 -1 0 0 -1 1.34536e-7 0 0 0.9996106 -0.02790832 -9.08455e-7 0.9984423 -0.05579531 0 0.9996105 -0.02790838 0 0.6868219 -0.7268257 0 0.6868233 -0.7268245 0 0.6868216 -0.7268261 -0.9863993 0.1625567 -0.02432841 -0.9870876 0.1601823 3.74961e-7 0 -0.1601832 0.9870873 -2.91577e-6 0.1601833 0.9870874 -4.58619e-6 0.1601836 0.9870873 -3.01884e-7 1 0 0 0.9870877 -0.160181 0 1 0 -7.64499e-7 1 0 0 0.9864322 -0.1641694 1 -3.47799e-7 0 0.9870873 0 -0.160184 1 -8.6103e-7 0 -1 0 8.83725e-7 -0.9997988 0 -0.02006179 0 1 -6.08475e-7 0 1 0 0 1 -2.62574e-7 6.58835e-7 -1 -3.61967e-7 2.27575e-7 -1 1.85834e-6 1.37451e-6 -1 -3.47637e-6 3.67429e-7 -1 1.0503e-6 -0.9873961 0 0.1582689 -0.7056326 0.7077814 -0.03358793 -0.7071078 0.7071058 2.88077e-7 -1 -1.77366e-7 0 -1 -2.59194e-7 0 -1 -1.08634e-6 -2.26119e-7 -0.9870874 -1.00426e-6 0.1601827 1 1.43892e-7 0 1 1.41894e-7 0 1 8.69075e-7 0 0.9870873 0 0.1601834 -1.62216e-6 0 1 4.04197e-7 0 1 -1.62215e-6 0 1 -8.43149e-6 0 1 3.85477e-7 0 1 -0.7055894 0.7053751 -0.06774622 -0.9859344 0.1599349 -0.04852157 6.23116e-7 0 1 -1 -1.28354e-7 -5.8239e-7 -1 -3.14853e-7 1.36214e-7 -1 -2.89083e-7 6.7306e-7 -1 -1.6335e-7 -1.42236e-7 -1 -2.53443e-7 -5.82434e-7 -1 -3.11797e-7 1.41806e-7 -1 -1.44527e-7 6.7299e-7 -1 -1.80924e-7 -1.36638e-7 -2.7322e-7 1 -1.28169e-6 -2.68087e-7 1 -4.33515e-6 -3.27087e-7 1 1.01145e-5 -2.72648e-7 1 3.5991e-6 2.66225e-7 1 -7.05927e-6 1.81969e-7 1 -1.2011e-6 -3.27087e-7 1 -1.01145e-5 2.72648e-7 1 4.28371e-6 0.278629 0.944534 0.1738432 -0.1212346 0.9439502 -0.3070186 0.2048742 0.9315166 0.3005055 -0.1997056 0.956891 -0.2108963 0.4373749 0.8984282 0.03911769 -0.2936673 0.9503622 -0.1028178 -0.1399397 0 0.9901601 -0.6827579 2.19769e-7 0.7306447 -0.7592791 0.626286 -0.1768086 -0.4373748 0.8984283 0.03911679 -0.466775 0.877353 -0.1112335 0.4667754 0.8773527 -0.1112343 0.2657519 0.7562027 -0.5979411 0.1997058 0.956891 -0.2108964 0.1212344 0.9439495 -0.3070207 0.596414 0.7752247 0.2081277 0.2145828 0.8739153 -0.4361496 0 0.6316556 -0.7752491 -0.08415716 0.8831208 -0.4615358 0 0.9029364 -0.4297742 0.01676148 0.961573 0.2740374 0 0.4824078 0.8759468 0 0.4824081 0.8759467 0 1 2.38382e-6 1.56916e-5 0.4801356 -0.8771943 0 0.9999967 -0.002594053 0.7248035 0.6816614 -0.09998899 0.3784909 0.9224358 0.07653123 0.2936674 0.9503622 -0.1028174 -0.05820691 0.9347166 -0.350595 0 1 2.0448e-6 -0.278629 0.9445341 0.173843 -0.2048748 0.9315176 0.300502 0.6827574 8.79077e-7 0.7306451 0 0 -1 0 0 1 0 0.4824088 0.8759463 0 0.4824078 0.8759468 0.9725064 0 -0.2328763 -0.7248028 0.6816621 -0.09998893 -0.3784908 0.9224358 0.07653099 -0.7664359 0.6282347 0.1337813 -0.5964137 0.7752248 0.2081283 -0.2145866 0.8739122 -0.4361538 -0.01676166 0.9615732 0.2740367 0 0.9999967 -0.002593874 0 1 2.18397e-6 -1.64872e-5 0.4801349 -0.8771947 -0.7055888 0.7053757 -0.06774663 -0.1598315 0.9852283 -0.06147646 -0.1598316 0.9852282 -0.0614773 -0.1074706 0.7218201 0.6836855 -0.2137191 0.2137195 0.9532304 -0.03424966 0.3147613 0.9485527 -0.4566128 0.453864 -0.7651878 -0.6756019 0.1117632 -0.7287462 -0.4545233 0.4559314 -0.7652027 0.6990306 0 -0.7150919 0.1601736 0 -0.9870889 0 1 -3.50263e-6 -0.1557462 0.9754872 0.1554601 0 0.9873964 0.1582666 0.1592839 0 -0.9872329 -0.1601737 0 -0.9870889 -0.7071094 -7.34056e-7 0.7071043 -0.9870873 -3.54703e-7 0.1601838 -0.999195 1.1817e-6 -0.04011684 -0.999195 -1.03848e-6 -0.04011684 -1 0 4.2077e-7 -1 0 5.83845e-7 0 1 0 0 0.9996106 -0.02790844 0 1 -2.46735e-6 0 0.9996106 -0.0279082 0 1 2.39763e-7 0 1 -9.60506e-7 1.19549e-6 0.9984423 -0.05579578 -2.92896e-6 0.9984422 -0.05579525 -0.9991958 -4.85718e-7 -0.04009848 -0.9991952 3.44828e-7 -0.04011243 -0.9991959 4.35812e-6 -0.040093 0 1 -2.47747e-7 0 1 -1.531e-6 0.9739219 1.35578e-7 -0.2268836 0.9848545 1.39577e-6 0.1733831 0.9739232 0 -0.2268784 0.984855 7.34335e-7 0.1733803 -0.3348194 0.8625779 -0.3792828 0.05820697 0.9347171 -0.3505939 0 0.4824079 0.8759468 0.9659467 0 0.2587413 0.9725065 0 -0.232876 -0.1652551 0 -0.9862509 -0.1744604 0 -0.9846643 -0.7077749 0.7031855 -0.06771242 -0.9859344 0.1599349 -0.04852175 -0.1601815 0.9870877 0 -0.6987373 0.6987359 0.1534094 -0.7218191 0.1074708 0.6836865 -0.5374588 0.5374578 0.6498287 -0.9754872 0.1557455 0.1554611 1.42234e-6 -0.9870871 0.1601847 5.45732e-7 -0.9870876 0.1601818 -0.1102728 0.6713883 -0.7328559 -0.6764709 0.1071243 -0.7286368 -0.6922408 0 -0.7216666 0 0.3199425 0.9474371 0 0.7098584 0.7043445 0 0.7098577 0.7043452 0 0.7071087 -0.7071049 0 0.7013254 -0.7128414 0 0.1601837 -0.9870873 -0.699027 0 -0.7150954 -0.3147523 0.0342499 0.9485557 -0.7098534 0 0.7043496 -0.3199265 0 0.9474424 2.24539e-7 0.9870874 0.1601827 0 0.7071084 0.7071052 0 0.9870879 0.1601805 -0.6922406 0 -0.7216668 -0.6922459 0 -0.7216617 -0.6922472 0 -0.7216605 1.44105e-7 -0.7071089 0.7071048 0 -0.1601842 0.9870872 0.7071012 0 0.7071124 -0.1601868 0 0.9870867 -0.1601868 0 0.9870868 -0.999195 6.25927e-7 -0.04011785 -5.93154e-7 0.9984424 -0.05579417 -2.20479e-7 1 1.59105e-6 0 1 -2.01709e-7 -2.58316e-7 1 -3.14524e-6 -0.9997988 -1.18688e-6 -0.02006363 -0.9997987 0 -0.02006202 -1.13216e-6 0.7071075 0.7071062 0 0.1595333 -0.9871926 0 -0.1601837 -0.9870873 0 0.9873963 0.158268 -0.999195 -2.74694e-6 -0.0401169 -0.9997988 0 -0.02006196 -0.9991951 7.54205e-7 -0.0401166 -0.1601819 0.9870876 0 -0.7071072 0.7071065 0 -0.1616261 0.9863744 -0.03070282 -3.20695e-7 0.9984423 -0.055794 -0.1567755 0.9857252 -0.06137925 -1.72794e-6 0.9996106 -0.02790677 -3.15784e-6 0.9984417 -0.05580544 -2.32463e-6 0.998442 -0.05579948 2.44768e-7 0.9984423 -0.05579525 2.15731e-6 0.9984413 -0.05581086 0 0.9984422 -0.05579513 -1 -2.12911e-7 -1.33787e-7 -1 -1.90789e-7 0 -1 -2.12911e-7 -1.33787e-7 -1 -2.65079e-7 0 -0.2190477 0.944662 0.2441968 0.08415734 0.8831216 -0.461534 -0.05801957 0.9170412 0.3945493 0 0.9033942 0.4288111 -0.9848547 6.50103e-7 0.1733821 -0.9739217 1.35578e-7 -0.2268845 -0.9739229 0 -0.2268792 -0.9848549 5.85297e-7 0.1733808 0.1744579 0 -0.9846646 0 0.9605016 0.2782745 0 0.9285686 -0.371161 -0.1157195 0.7098079 -0.694825 0 0.7124643 -0.7017084 -0.5178269 0.6479334 0.5586034 -0.1136556 0.6260161 0.7714833 -0.1291518 0.6237563 -0.7708747 -0.2657519 0.7562035 -0.5979402 -0.4900568 0.7793546 -0.3904494 0 0.6322342 0.7747774 0.11572 0.7098098 -0.694823 0.05801969 0.9170417 0.3945482 -0.1399398 0 0.9901601 0.9659466 0 0.2587417 0.5178269 0.6479336 0.5586031 0.2190478 0.944662 0.2441961 0.1291515 0.6237564 -0.7708748 0.334819 0.862578 -0.3792829 0.5132883 0.6309187 -0.5817876 0.4900574 0.7793549 -0.390448 0.1136562 0.6260171 0.7714823 0 0.7098587 0.7043442 0 0.3199425 0.947437 0 -0.7013257 -0.712841 -0.9870875 0.1601827 5.45838e-7 -0.107384 0.6719025 -0.7328135 0 0.686823 -0.7268248 0 0.6868231 -0.7268246 -0.9873963 0 0.1582678 -1 -2.19589e-7 0 -1 -1.35025e-7 0 1.60712e-6 -0.7071063 0.7071074 -0.9867233 0.1550676 -0.04828184 -1 -1.53571e-7 0 -0.7661256 0 -0.642691 -0.8661106 0 0.4998523 0.7592794 0.6262853 -0.1768093 0 -1 0 0 -1 0 0 -0.986432 -0.1641704 0 -0.7071088 -0.7071048 0 -0.7013252 -0.7128415 -2.58318e-7 1 0 -2.58318e-7 1 0 -2.64254e-7 1 0 0.9870879 0 -0.1601802 1 -2.17374e-7 0 1 -5.38144e-7 0 0.9861715 0 -0.1657288 0 0.9996106 -0.02790832 9.08456e-7 0.9984422 -0.05579549 -1.19549e-6 0.9984422 -0.05579507 0 0.6868247 -0.7268232 0 0.6868206 -0.726827 0 0.6868193 -0.7268282 0.9863992 0.1625571 -0.02432835 1 2.21695e-7 5.83388e-7 0.9997988 0 -0.02006214 4.22359e-6 0.1601836 0.9870873 0 -0.1601837 0.9870873 6.07714e-6 0.1601831 0.9870874 3.01884e-7 1 0 0 1 0 0 0.9870877 -0.1601809 7.645e-7 1 0 0 0.9864322 -0.1641693 -0.9870871 0 -0.1601846 1 3.38551e-7 8.83725e-7 0.9997988 0 -0.0200622 0.9997988 0 -0.02006214 0 1 0 -6.58833e-7 -1 -2.44686e-7 -1.37449e-6 -1 -3.47633e-6 -2.27572e-7 -1 -5.75571e-7 -3.6743e-7 -1 0 0.9873961 0 0.1582689 0.9870876 0.1601821 4.33979e-7 0.7056325 0.7077816 -0.03358781 0.7071084 0.7071052 3.06832e-7 1 -1.01534e-6 0 1 -8.69069e-7 -4.52238e-7 1 -3.62085e-7 0 0.9870875 -1.41099e-6 0.1601827 -1 -2.61068e-7 0 -1 -3.4763e-6 0 -1 1.17929e-6 0 -0.9870873 2.38802e-7 0.160184 1.62215e-6 0 1 -3.85477e-7 0 1 0.7055897 0.7053749 -0.06774628 -6.23115e-7 0 1 1 0 -5.8239e-7 1 -2.89083e-7 6.7306e-7 1 -3.0911e-7 1.36213e-7 1 0 -1.42236e-7 1 0 -5.82434e-7 1 -2.89053e-7 6.7299e-7 1 -6.18689e-7 1.41806e-7 1 0 -1.36638e-7 2.7322e-7 1 2.83455e-6 3.27087e-7 1 5.05724e-6 2.68087e-7 1 1.4304e-6 2.72648e-7 1 4.08379e-7 -2.66225e-7 1 -1.25295e-5 3.27087e-7 1 -1.68575e-6 -1.93693e-7 1 -3.94661e-7 -2.60924e-7 1 -1.74692e-6 -0.2786289 0.9445344 0.1738419 -0.2048746 0.9315176 0.3005021 0.1212341 0.9439495 -0.3070206 0.199705 0.9568908 -0.2108981 0.2936666 0.9503622 -0.1028185 -0.4373738 0.8984287 0.03911745 0.6827567 1.75815e-6 0.7306458 -0.4467669 0 -0.8946505 0.759279 0.6262863 -0.1768074 0.4373728 0.8984292 0.03911745 0.5964117 0.7752264 0.2081274 -0.4667755 0.8773527 -0.1112345 0.3784906 0.9224356 0.07653534 -0.2657517 0.7562034 -0.5979402 -0.199706 0.9568906 -0.2108983 -0.490056 0.7793557 -0.3904483 -0.5964134 0.7752251 0.2081277 -0.2145826 0.8739148 -0.4361504 0.08415722 0.883122 -0.4615336 0 0.6316536 -0.7752508 0 0.9029361 -0.429775 -0.01676154 0.9615729 0.2740378 0 0.4824079 0.8759468 0 0.9605017 0.2782744 0 1 2.52202e-6 -1.56916e-5 0.4801356 -0.8771944 -0.7248024 0.6816624 -0.09998863 -0.3784899 0.9224359 0.07653445 -0.766435 0.6282353 0.1337828 0.05820703 0.9347171 -0.3505939 0 1 2.52521e-6 0 0.9285693 -0.3711591 -0.1212345 0.9439496 -0.30702 0.2048748 0.9315175 0.3005022 0.2786284 0.9445343 0.1738423 -0.293667 0.9503621 -0.1028186 -0.6827589 0 0.7306438 0 0 -1 -0.1744615 0 -0.984664 0 0 1 0 0.4824092 0.875946 0 0.4824106 0.8759452 -0.6614933 0 -0.7499511 -0.9725064 0 -0.2328763 -0.6614952 0 -0.7499494 0.4667748 0.8773533 -0.1112313 0.7248014 0.6816636 -0.09998899 0.2145858 0.873916 -0.4361467 0.0167616 0.9615732 0.2740365 0 0.9999967 -0.002596616 0 1 2.51458e-6 1.64872e-5 0.480136 -0.8771941 0.7055886 0.7053759 -0.06774663 0.1598314 0.9852283 -0.0614764 0.1074706 0.7218199 0.6836857 0.2137202 0.2137196 0.9532302 0.5374588 0.5374581 0.6498284 0.4566127 0.4538648 -0.7651873 0.6756019 0.1117635 -0.7287462 0.6764709 0.1071243 -0.7286369 -0.160174 0 -0.9870889 -0.1592839 0 -0.9872329 0.1557461 0.9754874 0.15546 0 0.9873964 0.1582666 0.1601736 0 -0.9870889 0.7071093 -1.01094e-6 0.7071043 0.9870872 -3.87529e-7 0.160184 0.7071096 0 0.707104 0.999195 0 -0.0401172 1 0 4.2077e-7 0 0.9996105 -0.02790838 0 1 0 0 1 0 0 1 0 0 0.9996106 -0.02790844 0.9991952 5.35851e-7 -0.04011255 0.9991958 -3.07146e-7 -0.04009848 0.999196 5.54665e-6 -0.040093 -0.9848548 0 0.1733813 -0.9739217 0 -0.2268844 -0.9739229 0 -0.2268791 -0.4467697 0 -0.894649 -0.984855 0 0.1733806 0.3348196 0.8625776 -0.3792833 0.513288 0.6309184 -0.5817882 -0.05820685 0.9347169 -0.3505942 0 0.4824074 0.875947 0 0.4824079 0.8759467 0.4467671 0 -0.8946504 -0.9725065 0 -0.232876 0.1652553 0 -0.9862509 0.1744604 0 -0.9846643 0.7077753 0.703185 -0.06771254 0.9859343 0.1599354 -0.04852175 0.9867236 0.1550667 -0.0482819 0.6987362 0.6987369 0.1534097 0.1601815 0.9870877 1.37871e-7 0.7218199 0.1074712 0.6836856 0.9754872 0.1557461 0.155461 -1.42234e-6 -0.9870874 0.1601831 0.1102726 0.6713868 -0.7328572 0.1073837 0.6719009 -0.732815 0 0.3199409 0.9474376 0 0.7098588 0.7043441 0 0.3199428 0.947437 0 0.7071088 -0.7071048 0 0.7013258 -0.7128409 0 0.1601837 -0.9870873 0 0.1595335 -0.9871925 0.7071003 0 -0.7071134 0.6990271 0 -0.7150953 0.1592828 0 -0.987233 0.3147554 0.03425008 0.9485547 0.7098534 0 0.7043495 0 0.7071088 0.7071049 0 0.9870874 0.1601828 0 0.9870879 0.1601803 0.6922457 0 -0.7216619 0.6922406 0 -0.7216669 0.6922469 0 -0.7216608 -1.44105e-7 -0.7071074 0.7071062 -1.60712e-6 -0.7071076 0.707106 0.1601867 0 0.9870867 0.999195 8.09165e-7 -0.04011785 0 0.9996106 -0.02790832 0 1 -2.01709e-7 2.20479e-7 1 0 2.58316e-7 1 3.93155e-7 0.9997988 -1.36444e-6 -0.02006363 1 0 5.83845e-7 1.45202e-6 0.7071071 0.7071066 0 -0.160184 -0.9870873 0 0.9873965 0.1582665 0 0.7098582 0.7043447 0.9997988 0 -0.02006214 0.7071075 0.7071062 6.9705e-7 0.1601818 0.9870876 4.35845e-7 0.161626 0.9863744 -0.03070247 0.9859344 0.1599347 -0.04852157 0.1598315 0.9852282 -0.0614773 0.1567753 0.9857252 -0.06137931 3.20695e-7 0.9984425 -0.05579006 0 0.9984422 -0.05579572 2.90922e-6 0.9984423 -0.05579555 1.70379e-6 0.9996106 -0.02790689 3.10814e-6 0.9984416 -0.05580556 2.28732e-6 0.9984419 -0.05580008 -2.194e-6 0.9984415 -0.05581074 -2.53638e-7 0.9984422 -0.05579519 0 0.9984422 -0.05579519 0 1 -2.1935e-7 1 -2.37204e-7 0 1 -4.25821e-7 -1.33787e-7 1 -4.25821e-7 -1.33787e-7 0.999195 -2.50166e-6 -0.04011702 1 -5.23343e-7 0 0.2190474 0.9446619 0.2441968 -0.08415734 0.8831211 -0.4615351 -0.3348192 0.8625773 -0.3792844 0.05801981 0.9170417 0.3945482 0.9739216 2.71155e-7 -0.2268849 0.9848542 2.79154e-6 0.1733847 0.9739229 0 -0.2268797 0.9848548 1.46867e-6 0.1733814 -0.1744579 0 -0.9846646 0.1157202 0.7098101 -0.6948227 0.5178256 0.6479324 0.5586059 0.1291515 0.623755 -0.7708759 0.2657516 0.7562034 -0.5979403 0.1136567 0.6260176 0.7714818 0 0.9033944 0.4288109 -0.1157197 0.7098088 -0.694824 0.4900563 0.7793551 -0.3904491 -0.05801981 0.9170414 0.3945489 -1.12883e-5 0 -1 -0.8661081 0 0.4998567 -0.8661097 0 0.4998541 0 0.7124657 -0.701707 -0.517827 0.647933 0.5586038 -0.1291515 0.6237549 -0.7708759 -0.1136564 0.6260191 0.7714806 0 0.6322344 0.7747773 0 0.7098587 0.7043442 0.03424966 0.3147604 0.9485531 0 -0.1595338 -0.9871925 0.9870876 0.160182 6.11188e-7 0 0.6868243 -0.7268236 0.9873963 0 0.1582678 1 0 0 1 -2.68703e-7 0 1 -2.70051e-7 0 -5.45732e-7 -0.9870874 0.1601834 0.999195 0 -0.04011702 1 0 0 -0.2190482 0.9446614 0.2441983 0.9659469 0 0.2587408 -0.7592797 0.6262847 -0.1768105 0.1744571 0 -0.9846647 0 -0.6867119 -0.7269297 -0.06729674 -0.6492174 -0.7576199 0 -0.6867119 -0.7269297 -0.9990377 0 -0.04386013 -0.1282728 -0.6111344 -0.781064 -0.3953024 -0.3935441 -0.8299754 -0.9857621 -0.1598954 -0.05202376 -0.999027 0 -0.04410231 -0.9865199 -0.1550779 -0.05224269 -0.217175 -0.9704553 -0.1051266 0 -1 -1.21553e-7 0 -0.9984329 -0.05596268 -0.1563686 -0.9857413 -0.06215405 0 -0.9984329 -0.05596238 -0.1601857 -0.9870869 0 -0.9870879 -0.1601798 0 -0.9757663 0 -0.2188151 -0.9849669 -0.1647899 -0.05181384 -0.7055083 -0.7052023 -0.07034051 -0.7035986 -0.7071366 -0.07004874 -0.7071114 -0.7071023 0 -0.7071093 -0.7071043 0 -2.22209e-5 0 -1 -0.1726688 -0.9360496 0.3065887 -0.6565261 -0.6588346 0.3673016 -0.6585203 -0.6568337 0.3673155 -0.999042 0 -0.04376244 -0.9437708 -0.1312795 0.3034179 -0.9621601 0 0.2724851 -0.9345045 -0.1715559 0.3118814 -0.6532908 -0.067034 -0.7541337 -0.6911213 -8.46006e-7 -0.7227388 -0.6911211 -9.10077e-7 -0.7227391 -0.1306862 -0.945774 0.2973766 -1.6041e-6 -0.9641329 0.2654201 -1.1768e-6 -0.9641326 0.2654213 -0.1137749 -0.02512353 0.9931889 -0.06948345 -0.06875431 0.995211 -0.127994 -0.01102066 0.9917138 -0.6137746 -0.1293887 -0.7788065 0 -0.9984329 -0.05596309 -0.159867 -0.9851767 -0.06220543 -0.999027 0 -0.04410231 -0.691123 0 -0.7227373 -0.2173658 0.9705451 -0.1038967 -0.1941914 0 -0.9809637 -0.2171744 0.9704555 -0.1051262 -0.1390539 0 0.9902849 -0.1390535 0 0.990285 -0.6830195 0 -0.7304002 -0.1942855 0 -0.9809451 1.90284e-6 -0.9641329 0.26542 0.9743076 0 -0.2252216 -0.1632186 -0.9846245 -0.06224513 -0.03432196 -0.1030009 0.994089 -0.0343399 -0.1030031 0.9940882 -0.7070769 -0.7035985 -0.07065141 -0.6827533 0 -0.730649 0 -0.1361347 0.9906904 0 -0.1361348 0.9906904 0 -0.1361348 0.9906904 -0.2110617 0.9293981 -0.3027745 -0.2110544 -0.9293975 -0.3027809 -3.1363e-5 0 -1 -0.9990668 0 -0.04319185 -0.999067 0 -0.0431869 -0.999067 0 -0.04318851 -0.1601828 -0.9870874 0 0 -0.9641332 0.2654191 -0.9990541 0 -0.04348576 -0.204563 0.9277795 -0.3120564 0 -0.6867121 -0.7269296 0.06729638 -0.6492192 -0.7576184 0.1282731 -0.6111354 -0.7810631 0.9990378 0 -0.04386007 0.3953021 -0.3935477 -0.8299739 0.999027 0 -0.04410231 0.9857624 -0.1598939 -0.0520237 0.9865191 -0.1550832 -0.05224263 0.2160901 -0.9706843 -0.1052481 0.1563695 -0.9857411 -0.06215423 0.1598658 -0.9851769 -0.06220543 0.1601848 -0.9870871 0 0.9870879 -0.1601798 0 0.9870879 -0.1601798 0 0.9757666 0 -0.2188138 0.9849674 -0.1647864 -0.05181378 0.7055087 -0.7052019 -0.07034081 0.7071105 -0.7071031 0 0.7071096 -0.707104 0 2.96279e-5 0 -1 0.1726679 -0.9360501 0.3065876 0.6565286 -0.6588314 0.367303 0.130687 -0.9457736 0.2973774 0.999042 0 -0.04376238 0.9437712 -0.1312769 0.3034179 0.9621601 0 0.2724851 0.9621601 0 0.272485 0.6532908 -0.06703686 -0.7541335 0.6911213 -4.23003e-7 -0.7227388 0.6137745 -0.129389 -0.7788065 1.60409e-6 -0.964133 0.2654197 0.06948 -0.0687536 0.9952113 0.1137868 -0.02512389 0.9931875 0.127991 -0.01102048 0.9917141 0.9345049 -0.1715524 0.3118818 0.6585215 -0.6568323 0.3673157 0.3940048 -0.3948421 -0.829976 0.9990271 -3.46121e-7 -0.04410207 0.6911289 0 -0.7227315 0.2173643 0.9705454 -0.1038963 0.194188 0 -0.9809644 0.2171743 0.9704556 -0.1051261 0.1390539 0 0.9902849 0.6829755 0 -0.7304413 0.1942818 2.35761e-7 -0.9809458 0 -0.9641327 0.2654209 -0.9743076 0 -0.2252216 0.163218 -0.9846245 -0.06224566 0.7036007 -0.7071345 -0.07004982 0.03432196 -0.1030019 0.9940889 0.06895738 -0.06926524 0.9952122 0.7070736 -0.7036017 -0.07065123 0.6827404 0 -0.7306611 0 -0.1361348 0.9906904 0 -0.1361347 0.9906904 0 -0.1361346 0.9906904 0.2110545 0.9293987 -0.3027776 0.207488 -0.9267715 -0.3131187 0.9990668 5.25648e-7 -0.04319185 0.999067 -3.68801e-7 -0.0431869 0.999067 1.04203e-6 -0.04318851 0.1601834 -0.9870873 0 0 -0.9641331 0.2654192 0 -0.9641332 0.2654191 0.9990541 0 -0.04348593 0.2045649 0.9277796 -0.3120549 0 0.6867119 -0.7269297 -0.06729674 0.6492174 -0.7576199 -0.1282731 0.6111352 -0.7810633 -0.9990378 0 -0.04386007 -0.3953025 0.3935446 -0.8299751 -0.999027 0 -0.04410231 -0.9857621 0.1598954 -0.0520237 -0.9865199 0.1550779 -0.05224269 -0.2160901 0.9706843 -0.1052481 0 0.9984329 -0.05596268 -0.1563686 0.9857413 -0.06215405 -0.1598668 0.9851767 -0.06220567 -0.1601858 0.987087 0 -0.9870879 0.1601798 0 -0.9870879 0.1601798 0 -0.9757666 0 -0.2188138 -0.9849669 0.1647899 -0.05181372 -0.7055082 0.7052024 -0.07034087 -0.7071114 0.7071023 0 -0.7071093 0.7071043 0 -2.96279e-5 0 -1 -0.1726688 0.9360496 0.3065887 -0.6565262 0.6588346 0.3673014 -0.1306862 0.945774 0.2973766 -0.999042 0 -0.04376238 -0.9437709 0.1312795 0.3034177 -0.9621601 0 0.272485 -0.6532908 0.067034 -0.7541337 -0.6911213 8.46006e-7 -0.7227388 -0.6137746 0.1293887 -0.7788065 -1.6041e-6 0.9641329 0.2654201 -0.06948 0.06875431 0.9952113 -0.1137868 0.02512353 0.9931875 -0.127991 0.01102072 0.9917141 -0.9345044 0.1715559 0.3118817 -0.6585202 0.6568336 0.3673157 -0.3940042 0.3948456 -0.8299745 0 0.9984329 -0.05596309 -0.9990271 0 -0.04410207 -0.6911289 0 -0.7227315 -0.2173654 -0.9705452 -0.1038968 -0.194188 0 -0.9809644 -0.2171747 -0.9704554 -0.1051263 -0.6829755 0 -0.7304413 -0.1942818 0 -0.9809458 0 0.9641327 0.2654209 -0.1632186 0.9846245 -0.06224578 -0.7035986 0.7071366 -0.07004964 -0.03432196 0.1030009 0.994089 -0.06895738 0.06926435 0.9952123 -0.7070769 0.7035985 -0.07065141 -0.6827404 0 -0.7306611 0 0.1361348 0.9906904 0 0.1361348 0.9906904 0 0.1361348 0.9906904 -0.2110546 -0.9293986 -0.3027778 -0.2074874 0.926772 -0.3131177 -0.1601828 0.9870874 0 0 0.9641332 0.2654191 0 0.9641333 0.265419 -0.9990541 0 -0.04348593 -0.2045658 -0.927779 -0.3120562 0 0.6867121 -0.7269296 0.06729638 0.6492192 -0.7576184 0.9990377 0 -0.04386013 0.1282728 0.6111346 -0.7810638 0.3953019 0.3935472 -0.8299741 0.9857624 0.159894 -0.05202382 0.999027 0 -0.04410231 0.9865191 0.1550832 -0.05224263 0.2171747 0.9704554 -0.1051263 0 1 -1.21553e-7 0.1563695 0.9857411 -0.06215423 0 0.9984329 -0.05596238 0.1601848 0.9870871 0 0.9870879 0.1601798 0 0.9757663 0 -0.2188151 0.9849674 0.1647864 -0.05181384 0.7055088 0.7052018 -0.07034045 0.7036008 0.7071346 -0.07004892 0.7071105 0.7071031 0 0.7071096 0.707104 0 2.22209e-5 0 -1 0.1726679 0.9360501 0.3065876 0.6565285 0.6588314 0.3673031 0.6585215 0.6568324 0.3673155 0.999042 0 -0.04376244 0.9437712 0.1312769 0.303418 0.9345051 0.1715524 0.3118817 0.6532906 0.06703686 -0.7541335 0.6911213 4.23003e-7 -0.7227388 0.6911211 4.55038e-7 -0.7227391 0.130687 0.9457736 0.2973774 1.60409e-6 0.964133 0.2654197 1.1768e-6 0.9641327 0.2654211 0.1137749 0.02512389 0.9931889 0.06948345 0.0687536 0.995211 0.127994 0.01102048 0.9917138 0.6137745 0.129389 -0.7788063 0.159866 0.9851769 -0.06220525 0.999027 0 -0.04410231 0.691123 0 -0.7227373 0.2173648 -0.9705453 -0.1038963 0.1941914 0 -0.9809637 0.2171744 -0.9704555 -0.1051262 0.1390539 0 0.9902849 0.1390535 0 0.990285 0.6830195 0 -0.7304002 0.1942855 0 -0.9809451 -1.90284e-6 0.964133 0.2654196 0.163218 0.9846246 -0.06224501 0.03432196 0.1030019 0.9940889 0.0343399 0.1030019 0.9940883 0.7070736 0.7036017 -0.07065123 0.6827533 0 -0.730649 0 0.1361346 0.9906904 0 0.1361348 0.9906904 0 0.1361346 0.9906904 0.2110613 -0.9293982 -0.302774 0.2110543 0.9293977 -0.3027807 3.1363e-5 0 -1 0.9990668 -5.25648e-7 -0.04319185 0.999067 3.68801e-7 -0.0431869 0.999067 -1.04203e-6 -0.04318851 0.1601834 0.9870873 0 0 0.9641331 0.2654192 0.9990541 0 -0.04348576 0.2045624 -0.9277799 -0.3120554 2.58318e-7 -1 0 0 -0.6868237 -0.7268241 0 0.1601836 0.9870873 -0.9873961 0 0.1582689 0 0 1 -0.7664361 -0.6282345 0.1337814 -0.4545228 -0.455932 -0.7652027 -0.3199311 0 0.9474409 -0.6922394 0 -0.721668 -0.999195 0 -0.04011797 -5.93154e-7 -0.9984423 -0.05579417 0 -1 -2.89906e-7 0 -0.9873964 0.1582666 -0.999195 0 -0.0401166 0.5132883 -0.6309186 -0.5817877 0 -0.3199424 0.9474371 0 -0.6868233 -0.7268245 -2.58318e-7 -1 0 0 -0.6868259 -0.726822 0.9873961 0 0.1582689 -0.7664347 -0.6282351 0.1337857 0.7071097 0 0.7071039 0.3199311 0 0.9474409 0.513288 -0.6309184 -0.5817882 0 -0.3199428 0.947437 0.6922394 0 -0.721668 0.999195 0 -0.04011797 0 0.1595338 -0.9871925 0 -0.9873965 0.1582665 0 -0.9984422 -0.05579572 0 0.6868237 -0.7268241 -0.9997988 0 -0.02006173 0.7664358 0.6282345 0.1337829 -0.1592828 0 -0.987233 -0.5132883 0.6309195 -0.5817868 0 0.3199415 0.9474373 0 1 -2.89906e-7 0 -0.1595337 -0.9871925 0 0.9873964 0.1582666 0 0.9984422 -0.05579572 0 0.6868259 -0.726822 0 -0.1601837 0.9870873 0 0 1 0.7664363 0.6282329 0.1337866 0.4545233 0.4559328 -0.7652018 5.93155e-7 0.9984424 -0.05579239 0 1 -2.89906e-7 0 0.9873965 0.1582665 0.999195 0 -0.0401166 -0.5132883 0.6309177 -0.5817886 0 0.3199424 0.9474371 0 0.6868253 -0.7268226 -0.3940038 -0.3948445 -0.8299752 -0.2160901 -0.9706843 -0.1052481 -0.06894797 -0.06926435 0.9952129 4.15061e-5 0 1 -0.2161293 0.9708063 -0.1040351 -0.2160898 0.9706844 -0.1052483 0.9743075 0 -0.2252219 0 -0.1361349 0.9906904 0 -0.1361349 0.9906904 0 -0.1361348 0.9906904 -0.2074794 0.9267735 -0.3131187 -0.2074874 -0.926772 -0.3131177 0 -0.9641333 0.265419 -0.9990671 0 -0.0431872 -0.2083146 0.9305428 -0.3011565 0.2171747 -0.9704554 -0.1051263 -7.40691e-6 0 -1 0.6911211 -4.55038e-7 -0.7227391 1.1768e-6 -0.9641327 0.2654211 -5.53411e-5 0 1 0.2161294 0.9708064 -0.104035 0.2160898 0.9706844 -0.105248 0.1390535 0 0.990285 -1.90284e-6 -0.964133 0.2654196 -0.9743078 0 -0.2252207 0.0343399 -0.1030019 0.9940883 0 -0.1361349 0.9906904 0 -0.1361345 0.9906904 0.2074747 0.9267733 -0.3131228 0.2110543 -0.9293977 -0.3027807 0.999067 0 -0.04318749 0.2083198 0.9305419 -0.3011556 0 0.6867119 -0.7269297 -0.217175 0.9704553 -0.1051266 7.40691e-6 0 -1 -0.6911211 9.10077e-7 -0.7227391 -1.1768e-6 0.9641326 0.2654213 5.53411e-5 0 1 -0.2161294 -0.9708064 -0.104035 -0.2160901 -0.9706843 -0.1052482 1.90284e-6 0.9641329 0.26542 0.9743078 0 -0.2252207 -0.0343399 0.1030031 0.9940882 0 0.1361349 0.9906904 0 0.1361349 0.9906904 -0.2074739 -0.9267736 -0.3131217 -0.2110544 0.9293975 -0.3027809 -0.999067 0 -0.04318749 -0.2083194 -0.9305421 -0.3011552 0.3940044 0.394841 -0.8299766 0.2160901 0.9706843 -0.1052481 0.06894797 0.06926524 0.9952129 -4.15061e-5 0 1 0.9990271 3.46121e-7 -0.04410207 0.216129 -0.9708064 -0.104035 0.194188 0 -0.9809644 0.2160896 -0.9706844 -0.1052482 0.1942818 -2.35761e-7 -0.9809458 -0.9743075 0 -0.2252219 0 0.1361349 0.9906904 0 0.1361345 0.9906904 0.2074797 -0.9267733 -0.3131191 0.207488 0.9267715 -0.3131187 0 0.9641332 0.2654191 0.9990671 0 -0.0431872 0.2083148 -0.9305427 -0.3011568 - + - - -0.509955 0.238046 -0.500928 0.238046 -0.594754 0.238046 -0.621930 0.238046 -0.647400 0.238046 -0.634670 0.238046 -0.277685 0.238046 -0.289041 0.238046 -0.288927 0.352781 -0.277664 0.352753 -0.288558 0.507599 -0.288453 0.551719 -0.277192 0.551693 -0.277297 0.507572 -0.288562 0.049774 -0.277200 0.049777 -0.277192 0.013475 -0.288554 0.013473 -0.288606 0.163569 -0.277245 0.163573 -0.621677 0.353612 -0.634494 0.353644 -0.647178 0.353675 -0.634105 0.508429 -0.646789 0.508460 -0.042014 0.399207 -0.042173 0.622093 -0.023392 0.622107 -0.495139 0.357654 -0.495139 0.502252 -0.290098 0.502251 -0.015133 0.614196 -0.006348 0.399232 -0.005976 0.389640 -0.042007 0.389615 -0.005847 0.380047 -0.042001 0.380022 -0.005756 0.247125 -0.041911 0.247100 -0.005871 0.237532 -0.041904 0.237507 -0.006229 0.227939 -0.041898 0.227914 -0.341429 0.669267 -0.341521 0.630671 -0.351113 0.630864 -0.351021 0.669289 -0.360704 0.631396 -0.360613 0.669311 -0.646680 0.552582 -0.633996 0.552551 -0.621811 0.049686 -0.621799 0.013390 -0.634625 0.013386 -0.634637 0.049681 -0.231068 0.669005 -0.008144 0.668470 -0.008186 0.650941 -0.016125 0.642581 -0.231159 0.631083 -0.240753 0.630598 -0.240662 0.669028 -0.250347 0.630452 -0.250255 0.669050 -0.290098 0.357654 -0.292263 0.053667 -0.497084 0.053667 -0.480916 0.560508 -0.490508 0.560507 -0.490508 0.586476 -0.480916 0.586476 -0.471323 0.586476 -0.471323 0.560508 -0.338400 0.586476 -0.338400 0.560507 -0.328807 0.586476 -0.328807 0.560507 -0.319215 0.586476 -0.319215 0.560507 -0.647318 0.013382 -0.647331 0.049676 -0.621854 0.163467 -0.634683 0.163463 -0.647379 0.163459 -0.500306 0.552222 -0.500411 0.508101 -0.509808 0.160514 -0.512800 0.151544 -0.550900 0.152083 -0.550903 0.161100 -0.352952 0.595709 -0.352952 0.622199 -0.343359 0.622199 -0.343359 0.595709 -0.444126 0.622199 -0.444126 0.595710 -0.453719 0.595710 -0.453719 0.622199 -0.463312 0.622199 -0.463312 0.595710 -0.333767 0.622199 -0.333767 0.595709 -0.014711 0.012941 -0.022959 0.005017 -0.041742 0.005004 -0.575631 0.643924 -0.583527 0.652320 -0.583485 0.669845 -0.534442 0.560507 -0.534442 0.570203 -0.530321 0.582407 -0.497084 0.159746 -0.292263 0.159746 -0.600907 0.503904 -0.585307 0.505322 -0.585191 0.552430 -0.550298 0.552345 -0.550414 0.504976 -0.594800 0.163476 -0.621180 0.552519 -0.621289 0.508397 -0.512399 0.496181 -0.512724 0.365289 -0.550761 0.365434 -0.550436 0.496053 -0.582669 0.365463 -0.517958 0.586475 -0.291766 0.586475 -0.279402 0.582407 -0.275281 0.570204 -0.275281 0.560507 -0.490761 0.595710 -0.503125 0.599778 -0.507246 0.611982 -0.507246 0.622200 -0.289833 0.611981 -0.293954 0.599777 -0.306317 0.595709 -0.289833 0.622199 -0.600907 0.358516 -0.644841 0.358516 -0.644841 0.503904 -0.645767 0.158929 -0.601833 0.158929 -0.601833 0.055316 -0.645767 0.055316 -0.591806 0.501099 -0.591806 0.361322 -0.588772 0.492682 -0.588772 0.369739 -0.503511 0.360445 -0.582342 0.496354 -0.509757 0.356320 -0.500795 0.353310 -0.594647 0.353544 -0.585678 0.356509 -0.550783 0.356495 -0.509387 0.505135 -0.594261 0.508331 -0.594152 0.552452 -0.509273 0.552244 -0.585908 0.264616 -0.586026 0.238046 -0.585829 0.160489 -0.551013 0.264529 -0.506302 0.368816 -0.506302 0.491090 -0.503511 0.499461 -0.505447 0.056454 -0.505447 0.156959 -0.508234 0.064816 -0.508234 0.148597 -0.592732 0.156207 -0.592732 0.058039 -0.589698 0.148039 -0.589698 0.066207 -0.053836 0.006887 -0.271977 0.006887 -0.271977 0.051695 -0.551019 0.238046 -0.582836 0.151520 -0.512770 0.061681 -0.550870 0.062221 -0.582806 0.061658 -0.500826 0.163506 -0.509772 0.052712 -0.509761 0.013422 -0.550855 0.013411 -0.262281 0.051695 -0.262281 0.208885 -0.271977 0.208885 -0.271977 0.296529 -0.253221 0.315285 -0.206108 0.315285 -0.206108 0.305067 -0.268496 0.311803 -0.090666 0.305067 -0.090666 0.315285 -0.053835 0.315285 -0.053835 0.296385 -0.550867 0.053299 -0.594748 0.013398 -0.594760 0.049695 -0.585792 0.052688 -0.500787 0.049725 -0.500778 0.013424 -0.585779 0.013400 -0.621899 0.264706 -0.594869 0.264639 -0.509980 0.266718 -0.501011 0.267196 -0.647394 0.267370 -0.634714 0.265388 -0.289112 0.278497 -0.277846 0.280173 -0.500840 0.210537 -0.509824 0.210895 -0.594815 0.212515 -0.621870 0.212507 -0.634698 0.211852 -0.647394 0.209896 -0.277256 0.200514 -0.288618 0.202094 -0.585846 0.212518 -0.550919 0.212529 -0.063298 0.608889 -0.064356 0.624018 -0.072849 0.608221 -0.073906 0.623351 -0.059018 0.616834 -0.073380 0.615856 -0.088605 0.623383 -0.098176 0.623627 -0.088992 0.608221 -0.083977 0.615636 -0.098563 0.608466 -0.641416 0.636173 -0.594242 0.636173 -0.652737 0.636173 -0.520040 0.636173 -0.549914 0.636173 -0.533717 0.636173 -0.631208 0.636173 -0.578964 0.593583 -0.595183 0.582872 -0.548334 0.593975 -0.550405 0.599486 -0.600664 0.636173 -0.622756 0.636173 -0.620898 0.606294 -0.597315 0.614358 -0.537764 0.607027 -0.543266 0.608018 -0.546259 0.602368 -0.541724 0.598521 -0.606017 0.584028 -0.584923 0.595727 -0.590792 0.601939 -0.618560 0.590582 -0.538975 0.636173 -0.574129 0.600303 -0.552727 0.604521 -0.556745 0.611089 -0.572737 0.608178 -0.601573 0.574935 -0.598578 0.564875 -0.541748 0.581076 -0.546075 0.589034 -0.640359 0.602493 -0.652072 0.602236 -0.591238 0.616834 -0.583894 0.619802 -0.586507 0.636173 -0.532811 0.605736 -0.537916 0.595295 -0.531299 0.589493 -0.524464 0.602860 -0.550483 0.606202 -0.548038 0.609557 -0.554009 0.612938 -0.555398 0.611435 -0.640150 0.566562 -0.651953 0.566002 -0.621179 0.564708 -0.629249 0.567065 -0.098370 0.616003 -0.614952 0.557887 -0.616065 0.572913 -0.610143 0.561345 -0.579180 0.601789 -0.575824 0.609191 -0.543437 0.636173 -0.528602 0.636173 -0.584914 0.606245 -0.579411 0.611984 -0.629373 0.604187 -1.578964 0.593583 -1.550405 0.599486 -1.548334 0.593975 -1.595183 0.582872 -1.600664 0.636173 -1.597315 0.614358 -1.620898 0.606294 -1.622756 0.636173 -1.537764 0.607027 -1.541724 0.598521 -1.546259 0.602368 -1.543266 0.608018 -1.606017 0.584028 -1.618560 0.590582 -1.590792 0.601939 -1.584923 0.595727 -1.533717 0.636173 -1.538975 0.636173 -1.574129 0.600303 -1.572737 0.608178 -1.556745 0.611089 -1.552727 0.604521 -1.601573 0.574935 -1.546075 0.589034 -1.541748 0.581076 -1.598578 0.564875 -1.640359 0.602493 -1.652072 0.602236 -1.652737 0.636173 -1.641416 0.636173 -1.594242 0.636173 -1.586507 0.636173 -1.583894 0.619802 -1.591238 0.616834 -1.532811 0.605736 -1.524464 0.602860 -1.531299 0.589493 -1.537916 0.595295 -1.550483 0.606202 -1.555398 0.611435 -1.554009 0.612938 -1.548038 0.609557 -1.640151 0.566562 -1.651953 0.566002 -1.088992 0.608221 -1.098562 0.608466 -1.098370 0.616003 -1.083977 0.615636 -1.616065 0.572913 -1.610143 0.561345 -1.614952 0.557887 -1.621179 0.564708 -1.579180 0.601789 -1.575824 0.609191 -1.549914 0.636173 -1.543437 0.636173 -1.528602 0.636173 -1.520040 0.636173 -1.579411 0.611984 -1.584913 0.606245 -1.629373 0.604187 -1.631208 0.636173 -1.098176 0.623627 -1.088605 0.623383 -1.629249 0.567065 -1.500840 0.210537 -1.509824 0.210895 -1.509955 0.238046 -1.500928 0.238046 -1.621899 0.264706 -1.594869 0.264639 -1.594754 0.238046 -1.621930 0.238046 -1.509980 0.266718 -1.501011 0.267196 -1.594815 0.212515 -1.621870 0.212507 -1.634698 0.211852 -1.647393 0.209896 -1.647400 0.238046 -1.634670 0.238046 -1.647393 0.267370 -1.634714 0.265388 -1.289112 0.278497 -1.277846 0.280173 -1.277685 0.238046 -1.289042 0.238046 -1.277256 0.200514 -1.288618 0.202094 -1.288927 0.352781 -1.277664 0.352753 -1.288558 0.507599 -1.288453 0.551719 -1.277192 0.551693 -1.277297 0.507572 -1.042014 0.399207 -1.042173 0.622093 -1.023392 0.622107 -1.015133 0.614196 -1.006348 0.399232 -1.005976 0.389640 -1.042007 0.389615 -1.005847 0.380047 -1.042001 0.380022 -1.005756 0.247125 -1.041911 0.247100 -1.005871 0.237532 -1.041904 0.237507 -1.006229 0.227939 -1.041898 0.227914 -1.288562 0.049774 -1.277200 0.049777 -1.277192 0.013475 -1.288554 0.013473 -1.288606 0.163569 -1.277245 0.163573 -1.341429 0.669267 -1.341521 0.630671 -1.351113 0.630864 -1.351021 0.669289 -1.360704 0.631396 -1.360613 0.669311 -1.231068 0.669005 -1.008144 0.668470 -1.008186 0.650941 -1.016124 0.642581 -1.231159 0.631083 -1.240754 0.630598 -1.240662 0.669028 -1.250347 0.630452 -1.250255 0.669050 -1.621677 0.353612 -1.634494 0.353644 -1.647178 0.353675 -1.634105 0.508429 -1.646789 0.508460 -1.646680 0.552582 -1.633996 0.552551 -1.480916 0.560508 -1.490508 0.560507 -1.490508 0.586476 -1.480916 0.586476 -1.471323 0.586476 -1.471323 0.560508 -1.338400 0.586476 -1.338400 0.560507 -1.328807 0.586476 -1.328807 0.560507 -1.319215 0.586476 -1.319215 0.560507 -1.621811 0.049686 -1.621799 0.013390 -1.634625 0.013386 -1.634637 0.049681 -1.647318 0.013382 -1.647331 0.049676 -1.621854 0.163467 -1.634683 0.163463 -1.647379 0.163459 -1.352952 0.595709 -1.352952 0.622199 -1.343359 0.622199 -1.343359 0.595709 -1.444126 0.622199 -1.444126 0.595710 -1.453719 0.595710 -1.453719 0.622199 -1.463312 0.622199 -1.463312 0.595710 -1.333767 0.622199 -1.333767 0.595709 -1.500306 0.552222 -1.500411 0.508101 -1.014711 0.012941 -1.022959 0.005017 -1.041742 0.005004 -1.495139 0.357654 -1.495139 0.502252 -1.290098 0.502251 -1.290098 0.357654 -1.509808 0.160514 -1.512800 0.151544 -1.550900 0.152083 -1.550903 0.161100 -1.575631 0.643924 -1.583527 0.652320 -1.583485 0.669845 -1.292263 0.053667 -1.497084 0.053667 -1.497084 0.159746 -1.292263 0.159746 -1.585307 0.505322 -1.585191 0.552430 -1.550298 0.552345 -1.550414 0.504976 -1.534441 0.560507 -1.534442 0.570203 -1.530321 0.582407 -1.517958 0.586475 -1.291766 0.586475 -1.279402 0.582407 -1.275281 0.570204 -1.275281 0.560507 -1.600907 0.503904 -1.600907 0.358516 -1.644841 0.358516 -1.644841 0.503904 -1.053836 0.006887 -1.271977 0.006887 -1.271977 0.051695 -1.262281 0.051695 -1.594800 0.163476 -1.490761 0.595710 -1.503125 0.599778 -1.507246 0.611982 -1.507246 0.622200 -1.645767 0.158929 -1.601833 0.158929 -1.601833 0.055316 -1.645767 0.055316 -1.289833 0.611981 -1.293954 0.599777 -1.306317 0.595709 -1.289833 0.622199 -1.621180 0.552519 -1.621289 0.508397 -1.262281 0.208885 -1.271977 0.208885 -1.271977 0.296529 -1.253222 0.315285 -1.206108 0.315285 -1.206108 0.305067 -1.268496 0.311803 -1.090666 0.305067 -1.090666 0.315285 -1.053835 0.315285 -1.053835 0.296385 -1.512399 0.496181 -1.512724 0.365289 -1.550761 0.365434 -1.550436 0.496053 -1.582669 0.365463 -1.582342 0.496354 -1.509757 0.356320 -1.500795 0.353310 -1.594647 0.353544 -1.585678 0.356509 -1.550783 0.356495 -1.509387 0.505135 -1.594260 0.508331 -1.594152 0.552452 -1.509273 0.552244 -1.585908 0.264616 -1.586026 0.238046 -1.585846 0.212518 -1.585829 0.160489 -1.551013 0.264529 -1.551019 0.238046 -1.550920 0.212529 -1.582836 0.151520 -1.512770 0.061681 -1.550870 0.062221 -1.582806 0.061658 -1.500826 0.163506 -1.509772 0.052712 -1.509761 0.013422 -1.550855 0.013411 -1.550867 0.053299 -1.594748 0.013398 -1.594760 0.049695 -1.585792 0.052688 -1.500787 0.049725 -1.500778 0.013424 -1.585779 0.013400 -1.591806 0.501099 -1.591806 0.361322 -1.588772 0.492682 -1.588772 0.369739 -1.503511 0.360445 -1.506302 0.368816 -1.506302 0.491090 -1.503511 0.499461 -1.505447 0.056454 -1.505447 0.156959 -1.508234 0.064816 -1.508234 0.148597 -1.592732 0.156207 -1.592732 0.058039 -1.589698 0.148039 -1.589698 0.066207 -1.064356 0.624018 -1.059018 0.616834 -1.073380 0.615856 -1.073906 0.623351 -1.063298 0.608889 -1.072849 0.608221 -1.578964 0.593583 -1.550405 0.599486 -1.548334 0.593975 -1.595183 0.582872 -1.600664 0.636173 -1.597315 0.614358 -1.620898 0.606294 -1.622756 0.636173 -1.537764 0.607027 -1.541724 0.598521 -1.546259 0.602368 -1.543266 0.608018 -1.606017 0.584028 -1.618560 0.590582 -1.590792 0.601939 -1.584923 0.595727 -1.533717 0.636173 -1.538975 0.636173 -1.574129 0.600303 -1.572737 0.608178 -1.556745 0.611089 -1.552727 0.604521 -1.601573 0.574935 -1.546075 0.589034 -1.541748 0.581076 -1.598578 0.564875 -1.640359 0.602493 -1.652072 0.602236 -1.652737 0.636173 -1.641416 0.636173 -1.594242 0.636173 -1.586507 0.636173 -1.583894 0.619802 -1.591238 0.616834 -1.532811 0.605736 -1.524464 0.602860 -1.531299 0.589493 -1.537916 0.595295 -1.550483 0.606202 -1.555398 0.611435 -1.554009 0.612938 -1.548038 0.609557 -1.640151 0.566562 -1.651953 0.566002 -1.088992 0.608221 -1.098562 0.608466 -1.098370 0.616003 -1.083977 0.615636 -1.616065 0.572913 -1.610143 0.561345 -1.614952 0.557887 -1.621179 0.564708 -1.579180 0.601789 -1.575824 0.609191 -1.549914 0.636173 -1.543437 0.636173 -1.528602 0.636173 -1.520040 0.636173 -1.579411 0.611984 -1.584913 0.606245 -1.629373 0.604187 -1.631208 0.636173 -1.098176 0.623627 -1.088605 0.623383 -1.629249 0.567065 -2.578964 0.593583 -2.595183 0.582872 -2.548334 0.593975 -2.550405 0.599486 -2.600664 0.636173 -2.622756 0.636173 -2.620898 0.606294 -2.597315 0.614358 -2.537764 0.607027 -2.543266 0.608018 -2.546259 0.602368 -2.541724 0.598521 -2.606017 0.584028 -2.584923 0.595727 -2.590792 0.601939 -2.618560 0.590582 -2.533717 0.636173 -2.538975 0.636173 -2.574129 0.600303 -2.552727 0.604521 -2.556745 0.611089 -2.572737 0.608178 -2.601573 0.574935 -2.598578 0.564875 -2.541748 0.581076 -2.546075 0.589034 -2.640359 0.602493 -2.641416 0.636173 -2.652737 0.636173 -2.652072 0.602236 -2.594242 0.636173 -2.591238 0.616834 -2.583894 0.619802 -2.586507 0.636173 -2.532811 0.605736 -2.537916 0.595295 -2.531299 0.589493 -2.524464 0.602860 -2.550483 0.606202 -2.548038 0.609557 -2.554009 0.612938 -2.555398 0.611435 -2.640151 0.566562 -2.651953 0.566002 -2.088992 0.608221 -2.083977 0.615636 -2.098370 0.616003 -2.098562 0.608466 -2.616065 0.572913 -2.621179 0.564708 -2.614953 0.557887 -2.610143 0.561345 -2.579180 0.601789 -2.575824 0.609191 -2.543437 0.636173 -2.549914 0.636173 -2.528602 0.636173 -2.520040 0.636173 -2.584913 0.606245 -2.579411 0.611984 -2.631208 0.636173 -2.629373 0.604187 -2.088605 0.623383 -2.098176 0.623627 -2.629249 0.567065 -1.500840 0.210537 -1.509824 0.210895 -1.509955 0.238046 -1.500928 0.238046 -1.621899 0.264706 -1.594869 0.264639 -1.594754 0.238046 -1.621930 0.238046 -1.509980 0.266718 -1.501011 0.267196 -1.594815 0.212515 -1.621870 0.212507 -1.634698 0.211852 -1.647393 0.209896 -1.647400 0.238046 -1.634670 0.238046 -1.647393 0.267370 -1.634714 0.265388 -1.289112 0.278497 -1.277846 0.280173 -1.277685 0.238046 -1.289042 0.238046 -1.277256 0.200514 -1.288618 0.202094 -1.288927 0.352781 -1.277664 0.352753 -1.288558 0.507599 -1.288453 0.551719 -1.277192 0.551693 -1.277297 0.507572 -1.042014 0.399207 -1.042173 0.622093 -1.023392 0.622107 -1.015133 0.614196 -1.006348 0.399232 -1.005976 0.389640 -1.042007 0.389615 -1.005847 0.380047 -1.042001 0.380022 -1.005756 0.247125 -1.041911 0.247100 -1.005871 0.237532 -1.041904 0.237507 -1.006229 0.227939 -1.041898 0.227914 -1.288562 0.049774 -1.277200 0.049777 -1.277192 0.013475 -1.288554 0.013473 -1.288606 0.163569 -1.277245 0.163573 -1.341429 0.669267 -1.341521 0.630671 -1.351113 0.630864 -1.351021 0.669289 -1.360704 0.631396 -1.360613 0.669311 -1.231068 0.669005 -1.008144 0.668470 -1.008186 0.650941 -1.016124 0.642581 -1.231159 0.631083 -1.240754 0.630598 -1.240662 0.669028 -1.250347 0.630452 -1.250255 0.669050 -1.621677 0.353612 -1.634494 0.353644 -1.647178 0.353675 -1.634105 0.508429 -1.646789 0.508460 -1.646680 0.552582 -1.633996 0.552551 -1.480916 0.560508 -1.490508 0.560507 -1.490508 0.586476 -1.480916 0.586476 -1.471323 0.586476 -1.471323 0.560508 -1.338400 0.586476 -1.338400 0.560507 -1.328807 0.586476 -1.328807 0.560507 -1.319215 0.586476 -1.319215 0.560507 -1.621811 0.049686 -1.621799 0.013390 -1.634625 0.013386 -1.634637 0.049681 -1.647318 0.013382 -1.647331 0.049676 -1.621854 0.163467 -1.634683 0.163463 -1.647379 0.163459 -1.352952 0.595709 -1.352952 0.622199 -1.343359 0.622199 -1.343359 0.595709 -1.444126 0.622199 -1.444126 0.595710 -1.453719 0.595710 -1.453719 0.622199 -1.463312 0.622199 -1.463312 0.595710 -1.333767 0.622199 -1.333767 0.595709 -1.500306 0.552222 -1.500411 0.508101 -1.014711 0.012941 -1.022959 0.005017 -1.041742 0.005004 -1.495139 0.357654 -1.495139 0.502252 -1.290098 0.502251 -1.290098 0.357654 -1.509808 0.160514 -1.512800 0.151544 -1.550900 0.152083 -1.550903 0.161100 -1.575631 0.643924 -1.583527 0.652320 -1.583485 0.669845 -1.292263 0.053667 -1.497084 0.053667 -1.497084 0.159746 -1.292263 0.159746 -1.585307 0.505322 -1.585191 0.552430 -1.550298 0.552345 -1.550414 0.504976 -1.534441 0.560507 -1.534442 0.570203 -1.530321 0.582407 -1.517958 0.586475 -1.291766 0.586475 -1.279402 0.582407 -1.275281 0.570204 -1.275281 0.560507 -1.600907 0.503904 -1.600907 0.358516 -1.644841 0.358516 -1.644841 0.503904 -1.053836 0.006887 -1.271977 0.006887 -1.271977 0.051695 -1.262281 0.051695 -1.594800 0.163476 -1.490761 0.595710 -1.503125 0.599778 -1.507246 0.611982 -1.507246 0.622200 -1.645767 0.158929 -1.601833 0.158929 -1.601833 0.055316 -1.645767 0.055316 -1.289833 0.611981 -1.293954 0.599777 -1.306317 0.595709 -1.289833 0.622199 -1.621180 0.552519 -1.621289 0.508397 -1.262281 0.208885 -1.271977 0.208885 -1.271977 0.296529 -1.253222 0.315285 -1.206108 0.315285 -1.206108 0.305067 -1.268496 0.311803 -1.090666 0.305067 -1.090666 0.315285 -1.053835 0.315285 -1.053835 0.296385 -1.512399 0.496181 -1.512724 0.365289 -1.550761 0.365434 -1.550436 0.496053 -1.582669 0.365463 -1.582342 0.496354 -1.509757 0.356320 -1.500795 0.353310 -1.594647 0.353544 -1.585678 0.356509 -1.550783 0.356495 -1.509387 0.505135 -1.594260 0.508331 -1.594152 0.552452 -1.509273 0.552244 -1.585908 0.264616 -1.586026 0.238046 -1.585846 0.212518 -1.585829 0.160489 -1.551013 0.264529 -1.551019 0.238046 -1.550920 0.212529 -1.582836 0.151520 -1.512770 0.061681 -1.550870 0.062221 -1.582806 0.061658 -1.500826 0.163506 -1.509772 0.052712 -1.509761 0.013422 -1.550855 0.013411 -1.550867 0.053299 -1.594748 0.013398 -1.594760 0.049695 -1.585792 0.052688 -1.500787 0.049725 -1.500778 0.013424 -1.585779 0.013400 -1.591806 0.501099 -1.591806 0.361322 -1.588772 0.492682 -1.588772 0.369739 -1.503511 0.360445 -1.506302 0.368816 -1.506302 0.491090 -1.503511 0.499461 -1.505447 0.056454 -1.505447 0.156959 -1.508234 0.064816 -1.508234 0.148597 -1.592732 0.156207 -1.592732 0.058039 -1.589698 0.148039 -1.589698 0.066207 -1.064356 0.624018 -1.059018 0.616834 -1.073380 0.615856 -1.073906 0.623351 -1.063298 0.608889 -1.072849 0.608221 -1.578964 0.593583 -1.550405 0.599486 -1.548334 0.593975 -1.595183 0.582872 -1.600664 0.636173 -1.597315 0.614358 -1.620898 0.606294 -1.622756 0.636173 -1.537764 0.607027 -1.541724 0.598521 -1.546259 0.602368 -1.543266 0.608018 -1.606017 0.584028 -1.618560 0.590582 -1.590792 0.601939 -1.584923 0.595727 -1.533717 0.636173 -1.538975 0.636173 -1.574129 0.600303 -1.572737 0.608178 -1.556745 0.611089 -1.552727 0.604521 -1.601573 0.574935 -1.546075 0.589034 -1.541748 0.581076 -1.598578 0.564875 -1.640359 0.602493 -1.652072 0.602236 -1.652737 0.636173 -1.641416 0.636173 -1.594242 0.636173 -1.586507 0.636173 -1.583894 0.619802 -1.591238 0.616834 -1.532811 0.605736 -1.524464 0.602860 -1.531299 0.589493 -1.537916 0.595295 -1.550483 0.606202 -1.555398 0.611435 -1.554009 0.612938 -1.548038 0.609557 -1.640151 0.566562 -1.651953 0.566002 -1.088992 0.608221 -1.098562 0.608466 -1.098370 0.616003 -1.083977 0.615636 -1.616065 0.572913 -1.610143 0.561345 -1.614952 0.557887 -1.621179 0.564708 -1.579180 0.601789 -1.575824 0.609191 -1.549914 0.636173 -1.543437 0.636173 -1.528602 0.636173 -1.520040 0.636173 -1.579411 0.611984 -1.584913 0.606245 -1.629373 0.604187 -1.631208 0.636173 -1.098176 0.623627 -1.088605 0.623383 -1.629249 0.567065 -2.578964 0.593583 -2.595183 0.582872 -2.548334 0.593975 -2.550405 0.599486 -2.600664 0.636173 -2.622756 0.636173 -2.620898 0.606294 -2.597315 0.614358 -2.537764 0.607027 -2.543266 0.608018 -2.546259 0.602368 -2.541724 0.598521 -2.606017 0.584028 -2.584923 0.595727 -2.590792 0.601939 -2.618560 0.590582 -2.533717 0.636173 -2.538975 0.636173 -2.574129 0.600303 -2.552727 0.604521 -2.556745 0.611089 -2.572737 0.608178 -2.601573 0.574935 -2.598578 0.564875 -2.541748 0.581076 -2.546075 0.589034 -2.640359 0.602493 -2.641416 0.636173 -2.652737 0.636173 -2.652072 0.602236 -2.594242 0.636173 -2.591238 0.616834 -2.583894 0.619802 -2.586507 0.636173 -2.532811 0.605736 -2.537916 0.595295 -2.531299 0.589493 -2.524464 0.602860 -2.550483 0.606202 -2.548038 0.609557 -2.554009 0.612938 -2.555398 0.611435 -2.640151 0.566562 -2.651953 0.566002 -2.088992 0.608221 -2.083977 0.615636 -2.098370 0.616003 -2.098562 0.608466 -2.616065 0.572913 -2.621179 0.564708 -2.614953 0.557887 -2.610143 0.561345 -2.579180 0.601789 -2.575824 0.609191 -2.543437 0.636173 -2.549914 0.636173 -2.528602 0.636173 -2.520040 0.636173 -2.584913 0.606245 -2.579411 0.611984 -2.631208 0.636173 -2.629373 0.604187 -2.088605 0.623383 -2.098176 0.623627 -2.629249 0.567065 -1.500840 0.210537 -1.500928 0.238046 -1.509955 0.238046 -1.509824 0.210895 -1.621899 0.264706 -1.621930 0.238046 -1.594754 0.238046 -1.594869 0.264639 -1.501011 0.267196 -1.509980 0.266718 -1.621870 0.212507 -1.594815 0.212515 -1.634698 0.211852 -1.634670 0.238046 -1.647400 0.238046 -1.647393 0.209896 -1.634714 0.265388 -1.647393 0.267370 -1.289112 0.278497 -1.289042 0.238046 -1.277685 0.238046 -1.277846 0.280173 -1.288618 0.202094 -1.277256 0.200514 -1.277664 0.352753 -1.288927 0.352781 -1.288558 0.507599 -1.277297 0.507572 -1.277192 0.551693 -1.288453 0.551719 -1.042014 0.399207 -1.006348 0.399232 -1.015133 0.614196 -1.023392 0.622107 -1.042173 0.622093 -1.042007 0.389615 -1.005976 0.389640 -1.042001 0.380022 -1.005847 0.380047 -1.041911 0.247100 -1.005756 0.247125 -1.041904 0.237507 -1.005871 0.237532 -1.041898 0.227914 -1.006229 0.227939 -1.288562 0.049774 -1.288554 0.013473 -1.277192 0.013475 -1.277200 0.049777 -1.288606 0.163569 -1.277245 0.163573 -1.341429 0.669267 -1.351021 0.669289 -1.351113 0.630864 -1.341521 0.630671 -1.360613 0.669311 -1.360704 0.631396 -1.231068 0.669005 -1.231159 0.631083 -1.016124 0.642581 -1.008186 0.650941 -1.008144 0.668470 -1.240662 0.669028 -1.240754 0.630598 -1.250255 0.669050 -1.250347 0.630452 -1.621677 0.353612 -1.634494 0.353644 -1.647178 0.353675 -1.634105 0.508429 -1.633996 0.552551 -1.646680 0.552582 -1.646789 0.508460 -1.480916 0.560508 -1.480916 0.586476 -1.490508 0.586476 -1.490508 0.560507 -1.471323 0.586476 -1.471323 0.560508 -1.338400 0.586476 -1.338400 0.560507 -1.328807 0.586476 -1.328807 0.560507 -1.319215 0.586476 -1.319215 0.560507 -1.621811 0.049686 -1.634637 0.049681 -1.634625 0.013386 -1.621799 0.013390 -1.647331 0.049676 -1.647318 0.013382 -1.621854 0.163467 -1.634683 0.163463 -1.647379 0.163459 -1.352952 0.595709 -1.343359 0.595709 -1.343359 0.622199 -1.352952 0.622199 -1.444126 0.622199 -1.444126 0.595710 -1.453719 0.595710 -1.453719 0.622199 -1.463312 0.622199 -1.463312 0.595710 -1.333767 0.595709 -1.333767 0.622199 -1.500306 0.552222 -1.500411 0.508101 -1.014711 0.012941 -1.041742 0.005004 -1.022959 0.005017 -1.495139 0.357654 -1.290098 0.357654 -1.290098 0.502251 -1.495139 0.502252 -1.509808 0.160514 -1.550903 0.161100 -1.550900 0.152083 -1.512800 0.151544 -1.575631 0.643924 -1.583485 0.669845 -1.583527 0.652320 -1.292263 0.053667 -1.292263 0.159746 -1.497084 0.159746 -1.497084 0.053667 -1.585307 0.505322 -1.550414 0.504976 -1.550298 0.552345 -1.585191 0.552430 -1.517958 0.586475 -1.530321 0.582407 -1.534442 0.570203 -1.534441 0.560507 -1.291766 0.586475 -1.275281 0.560507 -1.275281 0.570204 -1.279402 0.582407 -1.600907 0.503904 -1.644841 0.503904 -1.644841 0.358516 -1.600907 0.358516 -1.053836 0.006887 -1.262281 0.051695 -1.271977 0.051695 -1.271977 0.006887 -1.594800 0.163476 -1.507246 0.622200 -1.507246 0.611982 -1.503125 0.599778 -1.490761 0.595710 -1.645767 0.158929 -1.645767 0.055316 -1.601833 0.055316 -1.601833 0.158929 -1.289833 0.611981 -1.289833 0.622199 -1.306317 0.595709 -1.293954 0.599777 -1.621180 0.552519 -1.621289 0.508397 -1.262281 0.208885 -1.206108 0.305067 -1.206108 0.315285 -1.253222 0.315285 -1.271977 0.296529 -1.271977 0.208885 -1.268496 0.311803 -1.090666 0.305067 -1.053835 0.296385 -1.053835 0.315285 -1.090666 0.315285 -1.512399 0.496181 -1.550436 0.496053 -1.550761 0.365434 -1.512724 0.365289 -1.582342 0.496354 -1.582669 0.365463 -1.509757 0.356320 -1.500795 0.353310 -1.594647 0.353544 -1.585678 0.356509 -1.550783 0.356495 -1.509387 0.505135 -1.594152 0.552452 -1.594260 0.508331 -1.509273 0.552244 -1.585908 0.264616 -1.586026 0.238046 -1.585846 0.212518 -1.585829 0.160489 -1.551013 0.264529 -1.551019 0.238046 -1.550920 0.212529 -1.582836 0.151520 -1.550870 0.062221 -1.512770 0.061681 -1.582806 0.061658 -1.500826 0.163506 -1.509772 0.052712 -1.550867 0.053299 -1.550855 0.013411 -1.509761 0.013422 -1.594748 0.013398 -1.594760 0.049695 -1.585792 0.052688 -1.500778 0.013424 -1.500787 0.049725 -1.585779 0.013400 -1.591806 0.361322 -1.591806 0.501099 -1.588772 0.369739 -1.588772 0.492682 -1.503511 0.360445 -1.503511 0.499461 -1.506302 0.491090 -1.506302 0.368816 -1.505447 0.156959 -1.505447 0.056454 -1.508234 0.148597 -1.508234 0.064816 -1.592732 0.058039 -1.592732 0.156207 -1.589698 0.066207 -1.589698 0.148039 -1.064356 0.624018 -1.073906 0.623351 -1.073380 0.615856 -1.059018 0.616834 -1.072849 0.608221 -1.063298 0.608889 -1.578964 0.593583 -1.595183 0.582872 -1.548334 0.593975 -1.550405 0.599486 -1.600664 0.636173 -1.622756 0.636173 -1.620898 0.606294 -1.597315 0.614358 -1.537764 0.607027 -1.543266 0.608018 -1.546259 0.602368 -1.541724 0.598521 -1.606017 0.584028 -1.584923 0.595727 -1.590792 0.601939 -1.618560 0.590582 -1.533717 0.636173 -1.538975 0.636173 -1.574129 0.600303 -1.552727 0.604521 -1.556745 0.611089 -1.572737 0.608178 -1.601573 0.574935 -1.598578 0.564875 -1.541748 0.581076 -1.546075 0.589034 -1.640359 0.602493 -1.641416 0.636173 -1.652737 0.636173 -1.652072 0.602236 -1.594242 0.636173 -1.591238 0.616834 -1.583894 0.619802 -1.586507 0.636173 -1.532811 0.605736 -1.537916 0.595295 -1.531299 0.589493 -1.524464 0.602860 -1.550483 0.606202 -1.548038 0.609557 -1.554009 0.612938 -1.555398 0.611435 -1.640151 0.566562 -1.651953 0.566002 -1.088992 0.608221 -1.083977 0.615636 -1.098370 0.616003 -1.098562 0.608466 -1.616065 0.572913 -1.621179 0.564708 -1.614952 0.557887 -1.610143 0.561345 -1.579180 0.601789 -1.575824 0.609191 -1.543437 0.636173 -1.549914 0.636173 -1.528602 0.636173 -1.520040 0.636173 -1.584913 0.606245 -1.579411 0.611984 -1.631208 0.636173 -1.629373 0.604187 -1.088605 0.623383 -1.098176 0.623627 -1.629249 0.567065 -2.578964 0.593583 -2.550405 0.599486 -2.548334 0.593975 -2.595183 0.582872 -2.600664 0.636173 -2.597315 0.614358 -2.620898 0.606294 -2.622756 0.636173 -2.537764 0.607027 -2.541724 0.598521 -2.546259 0.602368 -2.543266 0.608018 -2.606017 0.584028 -2.618560 0.590582 -2.590792 0.601939 -2.584923 0.595727 -2.533717 0.636173 -2.538975 0.636173 -2.574129 0.600303 -2.572737 0.608178 -2.556745 0.611089 -2.552727 0.604521 -2.601573 0.574935 -2.546075 0.589034 -2.541748 0.581076 -2.598578 0.564875 -2.640359 0.602493 -2.652072 0.602236 -2.652737 0.636173 -2.641416 0.636173 -2.594242 0.636173 -2.586507 0.636173 -2.583894 0.619802 -2.591238 0.616834 -2.532811 0.605736 -2.524464 0.602860 -2.531299 0.589493 -2.537916 0.595295 -2.550483 0.606202 -2.555398 0.611435 -2.554009 0.612938 -2.548038 0.609557 -2.640151 0.566562 -2.651953 0.566002 -2.088992 0.608221 -2.098562 0.608466 -2.098370 0.616003 -2.083977 0.615636 -2.616065 0.572913 -2.610143 0.561345 -2.614953 0.557887 -2.621179 0.564708 -2.579180 0.601789 -2.575824 0.609191 -2.549914 0.636173 -2.543437 0.636173 -2.528602 0.636173 -2.520040 0.636173 -2.579411 0.611984 -2.584913 0.606245 -2.629373 0.604187 -2.631208 0.636173 -2.098176 0.623627 -2.088605 0.623383 -2.629249 0.567065 -1.262281 0.006887 -1.262281 0.006887 -1.262281 0.006887 -0.262281 0.006887 -0.992633 0.473342 -0.236014 0.831592 -0.231256 0.452642 -0.972927 0.577680 -0.975829 0.583166 -0.442577 0.962489 -0.992633 0.210666 -0.480513 0.930627 -0.675717 0.962489 -0.236108 0.336894 -0.851290 0.583002 -0.231156 0.399649 -0.851394 0.577885 -0.239799 0.388204 -0.239799 0.517400 -0.239799 0.468551 -0.271984 0.831376 -0.272768 0.961728 -0.249461 0.961868 -0.248498 0.403037 -0.248585 0.449188 -0.215761 0.554936 -0.215329 0.326646 -0.077359 0.968226 -0.236108 0.388568 -0.253080 0.464409 -0.005205 0.968587 -0.231019 0.327494 -0.231399 0.528174 -0.012026 0.834817 -0.253080 0.392346 -0.256849 0.392056 -0.998765 0.210666 -0.981719 0.716999 -0.675717 0.992558 -0.998765 0.473342 -0.713971 0.930628 -0.442577 0.992558 -0.982423 0.732677 -0.851060 0.732582 -0.256849 0.464699 -0.236108 0.517714 -0.236108 0.468186 -0.992633 0.587900 -0.231450 0.554906 -0.381748 0.845024 -0.992633 0.483372 -0.713971 0.956094 -0.382211 0.901385 -0.063518 0.834559 -0.248742 0.531566 -0.256849 0.521140 -0.248786 0.554873 -0.480513 0.956094 -0.253066 0.521494 -0.364851 0.899360 -0.364851 0.846571 -0.407447 0.962489 -0.433148 0.962489 -0.334831 0.930628 -0.407447 0.980479 -0.471627 0.930627 -0.336926 0.992546 -0.471627 0.956094 -0.366812 0.980479 -0.433274 0.992546 -0.253066 0.557591 -0.256849 0.557591 -0.140297 0.962465 -0.094146 0.962710 -0.080625 0.832410 -0.152435 0.832029 -0.232672 0.967380 -0.157141 0.967803 -0.169564 0.833997 -0.218918 0.833721 -0.851063 0.716876 -0.998765 0.483372 -0.998765 0.587900 -0.334831 0.956095 -0.336926 0.962489 -0.239799 0.340611 -0.366812 0.962489 -0.991340 0.732126 -0.986902 0.732539 -0.986155 0.716839 -0.990581 0.716383 -0.978225 0.577554 -0.979836 0.583294 -0.983729 0.581993 -0.992633 0.478259 -0.437920 0.962489 -0.998765 0.478259 -0.476070 0.930627 -0.437920 0.992558 -0.982439 0.575272 -0.760296 0.738714 -0.764511 0.737309 -0.973855 0.737337 -0.973839 0.855766 -0.758875 0.855737 -0.476070 0.956094 -0.758890 0.742929 -0.298739 0.845949 -0.298739 0.879636 -0.298739 0.938598 -0.298739 0.964787 -0.282117 0.964787 -0.282117 0.830169 -0.026675 0.980329 -0.246888 0.980329 -0.263510 0.996108 -0.026675 0.996108 -0.317401 0.879636 -0.317401 0.938598 -0.251164 0.978946 -0.267786 0.994726 -0.346194 0.917335 -0.351016 0.899360 -0.364851 0.917335 -0.351016 0.846571 -0.346194 0.828623 -0.364851 0.828623 -0.252590 0.974798 -0.269211 0.990577 -1.760296 0.738714 -1.764511 0.737309 -1.973855 0.737337 -1.973839 0.855766 -1.758875 0.855737 -1.758890 0.742929 -1.236014 0.831592 -1.271984 0.831376 -1.272768 0.961728 -1.249461 0.961868 -1.480513 0.930627 -1.713971 0.930628 -1.713971 0.956094 -1.480513 0.956094 -1.992633 0.473342 -1.992633 0.210666 -1.998765 0.210666 -1.998765 0.473342 -1.298739 0.845949 -1.298739 0.879636 -1.298739 0.938598 -1.298739 0.964787 -1.282117 0.964787 -1.282117 0.830169 -1.442577 0.962489 -1.675717 0.962489 -1.675717 0.992558 -1.442577 0.992558 -1.972927 0.577680 -1.975829 0.583166 -1.851290 0.583002 -1.851394 0.577885 -1.981719 0.716999 -1.982423 0.732677 -1.851060 0.732582 -1.851063 0.716876 -1.077359 0.968226 -1.005205 0.968587 -1.012026 0.834817 -1.063518 0.834559 -1.140297 0.962465 -1.094146 0.962710 -1.080625 0.832410 -1.152435 0.832029 -1.232672 0.967380 -1.157141 0.967803 -1.169564 0.833997 -1.218917 0.833721 -1.236108 0.388568 -1.236108 0.336894 -1.239799 0.340611 -1.239799 0.388204 -1.253080 0.464409 -1.253080 0.392346 -1.256849 0.392056 -1.256849 0.464699 -1.236108 0.517714 -1.236108 0.468186 -1.239799 0.468551 -1.239799 0.517400 -1.256849 0.521140 -1.253066 0.521494 -1.231256 0.452642 -1.231156 0.399649 -1.248498 0.403037 -1.248585 0.449188 -1.334831 0.930628 -1.471627 0.930627 -1.471627 0.956094 -1.334831 0.956095 -1.992633 0.587900 -1.992633 0.483372 -1.998765 0.483372 -1.998765 0.587900 -1.381748 0.845024 -1.382211 0.901385 -1.364851 0.899360 -1.364851 0.846571 -1.026675 0.980329 -1.246888 0.980329 -1.263510 0.996108 -1.026675 0.996108 -1.253066 0.557591 -1.256849 0.557591 -1.215761 0.554936 -1.215329 0.326646 -1.231019 0.327494 -1.231399 0.528174 -1.231450 0.554906 -1.248742 0.531566 -1.248786 0.554873 -1.407447 0.962489 -1.433148 0.962489 -1.433274 0.992546 -1.407447 0.980479 -1.336926 0.992546 -1.366812 0.980479 -1.336926 0.962489 -1.366812 0.962489 -1.317401 0.879636 -1.317401 0.938598 -1.346194 0.917335 -1.351016 0.899360 -1.364851 0.917335 -1.351016 0.846571 -1.346194 0.828623 -1.364851 0.828623 -1.991340 0.732126 -1.986902 0.732539 -1.986155 0.716839 -1.990581 0.716383 -1.476070 0.930627 -1.476070 0.956094 -1.992633 0.478259 -1.998765 0.478259 -1.251164 0.978946 -1.267786 0.994726 -1.437920 0.962489 -1.437920 0.992558 -1.978225 0.577554 -1.979836 0.583294 -1.983729 0.581993 -1.252590 0.974798 -1.269212 0.990577 -1.982439 0.575272 -1.760296 0.738714 -1.764511 0.737309 -1.973855 0.737337 -1.973839 0.855766 -1.758875 0.855737 -1.758890 0.742929 -1.236014 0.831592 -1.271984 0.831376 -1.272768 0.961728 -1.249461 0.961868 -1.480513 0.930627 -1.713971 0.930628 -1.713971 0.956094 -1.480513 0.956094 -1.992633 0.473342 -1.992633 0.210666 -1.998765 0.210666 -1.998765 0.473342 -1.298739 0.845949 -1.298739 0.879636 -1.298739 0.938598 -1.298739 0.964787 -1.282117 0.964787 -1.282117 0.830169 -1.442577 0.962489 -1.675717 0.962489 -1.675717 0.992558 -1.442577 0.992558 -1.972927 0.577680 -1.975829 0.583166 -1.851290 0.583002 -1.851394 0.577885 -1.981719 0.716999 -1.982423 0.732677 -1.851060 0.732582 -1.851063 0.716876 -1.077359 0.968226 -1.005205 0.968587 -1.012026 0.834817 -1.063518 0.834559 -1.140297 0.962465 -1.094146 0.962710 -1.080625 0.832410 -1.152435 0.832029 -1.232672 0.967380 -1.157141 0.967803 -1.169564 0.833997 -1.218917 0.833721 -1.236108 0.388568 -1.236108 0.336894 -1.239799 0.340611 -1.239799 0.388204 -1.253080 0.464409 -1.253080 0.392346 -1.256849 0.392056 -1.256849 0.464699 -1.236108 0.517714 -1.236108 0.468186 -1.239799 0.468551 -1.239799 0.517400 -1.256849 0.521140 -1.253066 0.521494 -1.231256 0.452642 -1.231156 0.399649 -1.248498 0.403037 -1.248585 0.449188 -1.334831 0.930628 -1.471627 0.930627 -1.471627 0.956094 -1.334831 0.956095 -1.992633 0.587900 -1.992633 0.483372 -1.998765 0.483372 -1.998765 0.587900 -1.381748 0.845024 -1.382211 0.901385 -1.364851 0.899360 -1.364851 0.846571 -1.026675 0.980329 -1.246888 0.980329 -1.263510 0.996108 -1.026675 0.996108 -1.253066 0.557591 -1.256849 0.557591 -1.215761 0.554936 -1.215329 0.326646 -1.231019 0.327494 -1.231399 0.528174 -1.231450 0.554906 -1.248742 0.531566 -1.248786 0.554873 -1.407447 0.962489 -1.433148 0.962489 -1.433274 0.992546 -1.407447 0.980479 -1.336926 0.992546 -1.366812 0.980479 -1.336926 0.962489 -1.366812 0.962489 -1.317401 0.879636 -1.317401 0.938598 -1.346194 0.917335 -1.351016 0.899360 -1.364851 0.917335 -1.351016 0.846571 -1.346194 0.828623 -1.364851 0.828623 -1.991340 0.732126 -1.986902 0.732539 -1.986155 0.716839 -1.990581 0.716383 -1.476070 0.930627 -1.476070 0.956094 -1.992633 0.478259 -1.998765 0.478259 -1.251164 0.978946 -1.267786 0.994726 -1.437920 0.962489 -1.437920 0.992558 -1.978225 0.577554 -1.979836 0.583294 -1.983729 0.581993 -1.252590 0.974798 -1.269212 0.990577 -1.982439 0.575272 -1.760296 0.738714 -1.758890 0.742929 -1.758875 0.855737 -1.973839 0.855766 -1.973855 0.737337 -1.764511 0.737309 -1.236014 0.831592 -1.249461 0.961868 -1.272768 0.961728 -1.271984 0.831376 -1.480513 0.930627 -1.480513 0.956094 -1.713971 0.956094 -1.713971 0.930628 -1.992633 0.473342 -1.998765 0.473342 -1.998765 0.210666 -1.992633 0.210666 -1.298739 0.845949 -1.282117 0.830169 -1.282117 0.964787 -1.298739 0.964787 -1.298739 0.938598 -1.298739 0.879636 -1.442577 0.962489 -1.442577 0.992558 -1.675717 0.992558 -1.675717 0.962489 -1.972927 0.577680 -1.851394 0.577885 -1.851290 0.583002 -1.975829 0.583166 -1.981719 0.716999 -1.851063 0.716876 -1.851060 0.732582 -1.982423 0.732677 -1.077359 0.968226 -1.063518 0.834559 -1.012026 0.834817 -1.005205 0.968587 -1.140297 0.962465 -1.152435 0.832029 -1.080625 0.832410 -1.094146 0.962710 -1.232672 0.967380 -1.218917 0.833721 -1.169564 0.833997 -1.157141 0.967803 -1.236108 0.388568 -1.239799 0.388204 -1.239799 0.340611 -1.236108 0.336894 -1.253080 0.464409 -1.256849 0.464699 -1.256849 0.392056 -1.253080 0.392346 -1.236108 0.517714 -1.239799 0.517400 -1.239799 0.468551 -1.236108 0.468186 -1.253066 0.521494 -1.256849 0.521140 -1.231256 0.452642 -1.248585 0.449188 -1.248498 0.403037 -1.231156 0.399649 -1.334831 0.930628 -1.334831 0.956095 -1.471627 0.956094 -1.471627 0.930627 -1.992633 0.587900 -1.998765 0.587900 -1.998765 0.483372 -1.992633 0.483372 -1.381748 0.845024 -1.364851 0.846571 -1.364851 0.899360 -1.382211 0.901385 -1.026675 0.980329 -1.026675 0.996108 -1.263510 0.996108 -1.246888 0.980329 -1.253066 0.557591 -1.256849 0.557591 -1.215761 0.554936 -1.231450 0.554906 -1.231399 0.528174 -1.231019 0.327494 -1.215329 0.326646 -1.248786 0.554873 -1.248742 0.531566 -1.407447 0.962489 -1.407447 0.980479 -1.433274 0.992546 -1.433148 0.962489 -1.366812 0.980479 -1.336926 0.992546 -1.366812 0.962489 -1.336926 0.962489 -1.317401 0.938598 -1.317401 0.879636 -1.346194 0.917335 -1.364851 0.917335 -1.351016 0.899360 -1.351016 0.846571 -1.364851 0.828623 -1.346194 0.828623 -1.991340 0.732126 -1.990581 0.716383 -1.986155 0.716839 -1.986902 0.732539 -1.476070 0.956094 -1.476070 0.930627 -1.998765 0.478259 -1.992633 0.478259 -1.267786 0.994726 -1.251164 0.978946 -1.437920 0.992558 -1.437920 0.962489 -1.979836 0.583294 -1.978225 0.577554 -1.983729 0.581993 -1.269212 0.990577 -1.252590 0.974798 -1.982439 0.575272 - + + 0.9182865 0.3786976 0.9182868 0.592559 0.9002661 0.5925588 0.9182865 0.3786976 0.9002661 0.5925588 0.892347 0.5849624 0.9182865 0.3786976 0.892347 0.5849624 0.8840656 0.3786978 0.9182864 0.3694939 0.8840656 0.3786978 0.883715 0.3694932 0.1566444 0.3412187 0.04588252 0.2990664 0.1566444 0.2990664 0.9571333 0.3386409 0.9571333 0.5525013 0.9403162 0.5525014 0.9571333 0.3386409 0.9403162 0.5525014 0.9322776 0.5449053 0.9571333 0.3386409 0.9322776 0.5449053 0.9207512 0.3386411 0.4605653 0.2528128 0.3739025 0.2140727 0.4605651 0.2140728 0.4280855 0.1316481 0.4634221 0.1205881 0.4634221 0.1316481 0.2725553 0.2528129 0.1882316 0.28561 0.1882315 0.252813 0.9201011 0.7424094 0.9450164 0.6148759 0.9450165 0.7424094 0.4326246 0.4419285 0.4756163 0.4326248 0.4756165 0.4419285 0.9002658 4.88286e-4 0.9182864 4.88286e-4 0.9182865 0.2143492 0.8923468 0.008084595 0.9002658 4.88286e-4 0.9182865 0.2143492 0.8923468 0.008084595 0.9182865 0.2143492 0.8840655 0.2143492 0.9403161 4.88303e-4 0.9571329 4.88287e-4 0.9571332 0.2143483 0.9322778 0.008084475 0.9403161 4.88303e-4 0.9571332 0.2143483 0.9322778 0.008084475 0.9571332 0.2143483 0.9207516 0.2143484 0.1792764 0.28561 0.05301839 0.2528129 0.1792763 0.2528129 0.9357133 0.8029695 0.924004 0.7990155 0.9201009 0.7871531 0.9450165 0.8029695 0.9357133 0.8029695 0.9201009 0.7871531 0.9201009 0.570132 0.924004 0.5582697 0.9357133 0.5543157 0.9201009 0.570132 0.9357133 0.5543157 0.9450165 0.5543156 4.88303e-4 0.3205851 0.04406833 0.3329567 4.88307e-4 0.3329567 0.2725553 0.2856099 0.2955789 0.252813 0.295579 0.2856099 0.1932691 0.907238 0.2051314 0.9111408 0.2090855 0.9228498 0.166933 0.9072378 0.1932691 0.907238 0.2090855 0.9228498 4.88282e-4 0.92285 0.004442393 0.9111411 0.01630425 0.907238 4.88282e-4 0.92285 0.01630425 0.907238 0.04264056 0.9072379 0.7285192 0.4506204 0.7285192 0.4958242 0.7187155 0.4958242 0.7105237 0.4326251 0.7285192 0.4506204 0.7187155 0.4958242 0.7105237 0.4326251 0.7251788 0.4359653 0.7285192 0.4506204 0.6264333 0.4419283 0.7187155 0.4958242 0.4326246 0.6419227 0.2725553 0.2528129 0.295579 0.2140727 0.2955789 0.252813 0.7187155 0.4958242 0.7187154 0.6065858 0.4326246 0.6419227 0.4326246 0.6419227 0.4756165 0.4419285 0.6264333 0.4419283 0.7187154 0.6065858 0.7103851 0.6419227 0.4326246 0.6419227 0.7311023 0.7581059 0.8586355 0.7581059 0.867367 0.7610166 0.867367 0.7610166 0.7223711 0.7610161 0.7311023 0.7581059 0.8701421 0.5603047 0.7426085 0.5603047 0.7338771 0.5573942 0.7338771 0.5573942 0.8788734 0.5573942 0.8701421 0.5603047 0.7190892 0.9275556 0.7190891 0.8400775 0.7219994 0.831346 0.7219994 0.831346 0.7219995 0.9362868 0.7190892 0.9275556 0.05752444 0.2874242 0.1450024 0.2874242 0.153734 0.2903351 0.153734 0.2903351 0.04879301 0.2903351 0.05752444 0.2874242 0.1491801 0.07562226 0.1416816 0.0840274 0.1360535 0.05899429 0.1427766 0.05496656 0.1459805 0.04982274 0.1526682 0.06678771 0.4496341 0.9265977 0.4541367 0.9357835 0.449634 0.9357835 0.5652344 0.9357835 0.5775492 0.9265977 0.5775492 0.9357835 0.4444977 0.9247831 0.456524 0.9155978 0.456524 0.9247831 0.3797456 0.9265977 0.4000297 0.9357835 0.3797456 0.9357835 0.04735714 0.01762789 0.05183398 0.06548821 0.04588836 0.07377058 0.1522934 0.02071493 0.1459805 0.04982274 0.1459411 0.02213335 0.07155132 0.05187094 0.0620597 0.053842 0.06636029 0.04771524 0.1491801 0.07562226 0.1526682 0.06678771 0.1583899 0.07515925 0.1583899 0.07515925 0.153132 0.08474558 0.1491801 0.07562226 0.06827884 0.006764054 0.1032041 4.88464e-4 0.1031009 0.006463944 0.1416816 0.0840274 0.153132 0.08474558 0.1293473 0.09187269 0.1276409 0.1844576 0.1010712 0.1931164 0.1010711 0.1844576 0.1293473 0.09187269 0.1282298 0.0844019 0.1416816 0.0840274 0.1416816 0.0840274 0.1491801 0.07562226 0.153132 0.08474558 0.1562597 0.1758696 0.1562597 0.1844575 0.1276409 0.1844576 0.1276409 0.1844576 0.149798 0.1758696 0.1562597 0.1758696 0.06446784 0.04335635 0.05961465 0.0207507 0.06499302 0.02227306 0.123577 0.06251293 0.1021029 0.08445197 0.1023678 0.06344956 0.06873148 0.05807965 0.06246048 0.08306509 0.05513036 0.07444918 0.05183398 0.06548821 0.05894839 0.04857367 0.0620597 0.053842 0.5234426 0.9357835 0.5279453 0.9265979 0.5279453 0.9357835 0.5056975 0.9155978 0.5411367 0.9247834 0.5056976 0.9247834 0.4887897 0.9357835 0.5234427 0.9265977 0.5234426 0.9357835 0.07352977 0.1931163 0.04588282 0.2023016 0.04588282 0.193116 0.3899179 0.9247831 0.4444976 0.9155978 0.4444977 0.9247831 0.5548712 0.9155978 0.5668978 0.9247831 0.5548712 0.9247831 0.05326932 0.01916384 0.05894839 0.04857367 0.05183398 0.06548821 0.1406086 0.0445531 0.1459411 0.02213335 0.1459805 0.04982274 0.05513036 0.07444918 0.05094891 0.0835188 0.04588836 0.07377058 0.04588836 0.07377058 0.05183398 0.06548821 0.05513036 0.07444918 0.06246048 0.08306509 0.07465165 0.0912249 0.05094891 0.0835188 0.04588252 0.1844576 0.07352977 0.1931163 0.04588282 0.193116 0.07465165 0.0912249 0.06246048 0.08306509 0.07595032 0.08376377 0.06246048 0.08306509 0.05094891 0.0835188 0.05513036 0.07444918 0.04588252 0.1758695 0.0523439 0.1758695 0.07450091 0.1844576 0.07450091 0.1844576 0.04588252 0.1844576 0.04588252 0.1758695 0.295579 0.205219 0.3186024 0.2140727 0.295579 0.2140727 0.3186025 0.3329197 0.2955789 0.3452492 0.295579 0.3329195 0.8842406 0.9410114 0.8623856 0.952134 0.8623856 0.9410116 0.9202634 0.223552 0.9571331 0.2327558 0.9201009 0.2327558 0.3186025 0.3205383 0.3649247 0.2944475 0.3649247 0.3205381 0.9571332 0.3202335 0.9201009 0.2327558 0.9571331 0.2327558 0.1577292 0.907238 0.1669332 0.9326535 0.1577293 0.9326534 0.04406833 0.3329567 4.8831e-4 0.3452001 4.88307e-4 0.3329567 0.04264074 0.9326536 4.88282e-4 0.92285 0.04264056 0.9072379 0.728519 0.6419227 0.7187154 0.6065858 0.7285189 0.6065858 0.05301839 0.2528129 0.1792763 0.2140728 0.1792763 0.2528129 0.04264056 0.9072379 0.05184453 0.9326536 0.04264074 0.9326536 4.88281e-4 0.28561 0.04406827 0.2944945 4.88297e-4 0.2944943 0.3649246 0.252813 0.3739026 0.28561 0.3649247 0.28561 0.3739026 0.28561 0.4605653 0.2528128 0.4605652 0.2856102 0.4695122 0.2528128 0.4605652 0.2856102 0.4605653 0.2528128 0.4605651 0.2140728 0.4695122 0.2528128 0.4605653 0.2528128 0.04406833 0.2051816 4.88345e-4 0.2140725 4.88343e-4 0.2051817 0.4695124 0.2944943 0.5055451 0.2856101 0.5055453 0.2944943 0.04588252 0.2990664 0.153734 0.2903351 0.1566444 0.2990664 0.5309278 0.9357835 0.5530718 0.9265979 0.5530717 0.9357835 0.558196 0.9357835 0.5652345 0.9265977 0.5652344 0.9357835 0.5279453 0.9357835 0.5309278 0.9265979 0.5309278 0.9357835 0.05789202 0.01086807 0.04735714 0.01762789 0.05387437 0.006297409 0.0458827 0.09480309 0.05506843 0.1021202 0.04588252 0.1021202 0.07595032 0.08376377 0.06873148 0.05807965 0.08117532 0.06195604 0.1562597 0.2023016 0.1286125 0.1931164 0.1562598 0.1931163 0.4123449 0.9265977 0.4193831 0.9357835 0.4123449 0.9357835 0.5668975 0.9155978 0.6214771 0.9247831 0.5668978 0.9247831 0.4000297 0.9265977 0.4123449 0.9357835 0.4000297 0.9357835 0.4702587 0.9247834 0.5056975 0.9155978 0.5056976 0.9247834 0.2955788 4.88289e-4 0.2725553 0.2052192 0.2725554 4.88297e-4 0.2955789 0.3205384 0.3186024 0.2944474 0.3186025 0.3205383 0.2955789 0.3452492 0.2725553 0.3329195 0.295579 0.3329195 0.3186025 0.3205383 0.295579 0.3329195 0.2955789 0.3205384 0.295579 0.3329195 0.2725553 0.3205384 0.2955789 0.3205384 0.9450165 0.5964685 0.9201009 0.570132 0.9450165 0.5543156 0.9060957 0.9521344 0.8842406 0.9410114 0.9060957 0.9410116 0.7914544 0.9521344 0.8623856 0.9410116 0.8623856 0.952134 0.4695124 0.3452002 0.5055454 0.3329566 0.5055454 0.3452002 0.8840655 0.2143492 0.9182864 0.2235528 0.883715 0.2235527 0.883715 0.2235527 0.9182868 0.2327569 0.8835983 0.2327569 0.9571332 0.3294374 0.9207512 0.3386411 0.9202635 0.3294375 0.9571332 0.3202335 0.9202635 0.3294375 0.9201007 0.3202334 0.2725553 0.3452491 0.1882315 0.3329193 0.2725553 0.3329195 0.9201009 0.7516131 0.9450165 0.7608169 0.9201009 0.7608169 0.1230109 0.05257523 0.08001965 0.04160183 0.1230109 0.04160183 0.9450164 0.6148759 0.9201011 0.6056721 0.9450164 0.6056721 0.9207516 0.2143484 0.9571331 0.2235522 0.9202634 0.223552 0.05184429 0.9072378 0.06104815 0.9326534 0.05184453 0.9326536 0.1485259 0.9326536 0.1577292 0.907238 0.1577293 0.9326534 0.04406827 0.2944945 4.88303e-4 0.3205851 4.88297e-4 0.2944943 4.88343e-4 0.2051817 0.04406833 6.73867e-4 0.04406833 0.2051816 0.3649246 0.252813 0.3739025 0.2140727 0.3739025 0.2528129 0.944592 0.8284353 0.730731 0.9391972 0.7307309 0.8284351 4.88342e-4 0.2528129 0.04406827 0.28561 4.88281e-4 0.28561 0.9450165 0.7516131 0.9201011 0.7424094 0.9450165 0.7424094 0.9182865 0.36029 0.8835983 0.2327569 0.9182868 0.2327569 0.7105237 0.4326251 0.6264333 0.4419283 0.6264333 0.4326247 0.4695122 0.3205853 0.5055454 0.3329566 0.4695124 0.3329566 0.04406833 0.2528129 0.05301839 0.2140728 0.05301839 0.2528129 0.1792763 0.2140728 0.1882315 0.252813 0.1792763 0.2528129 0.295579 0.2944474 0.3186024 0.2856103 0.3186024 0.2944474 0.295579 0.2856099 0.3186024 0.2528129 0.3186024 0.2856103 0.3649247 0.2944475 0.3186024 0.2856103 0.3649247 0.28561 0.3186024 0.2856103 0.3649246 0.252813 0.3649247 0.28561 0.2725553 0.2140727 0.1882316 0.2052192 0.2725553 0.2052192 0.295579 0.2140727 0.3186024 0.2528129 0.2955789 0.252813 0.1882315 0.252813 0.2725553 0.2140727 0.2725553 0.2528129 0.3186024 0.2052192 0.2955788 4.88289e-4 0.3186025 4.88513e-4 0.3649247 0.2052192 0.3186025 4.88513e-4 0.3649246 4.88281e-4 0.4695124 0.2140727 0.5055453 0.2528129 0.4695122 0.2528128 0.5055453 0.2140728 0.4695124 0.2051753 0.5055453 0.2051752 0.5055453 0.2051752 0.4695123 5.12323e-4 0.5055453 5.12315e-4 0.5055453 0.2528129 0.4695124 0.2856102 0.4695122 0.2528128 0.8817839 0.5486628 0.7309666 0.3348015 0.8817839 0.3348016 4.88342e-4 0.2528129 0.04406833 0.2140728 0.04406833 0.2528129 0.7309666 0.5486626 0.8788734 0.5573942 0.7338771 0.5573942 0.730731 0.9391972 0.7219994 0.831346 0.7307309 0.8284351 0.1434301 0.01716881 0.1377221 0.007961034 0.1479231 0.01234704 0.1526682 0.06678771 0.1360535 0.05899429 0.1427766 0.05496656 0.1369493 0.01433765 0.1031009 0.006463944 0.1377221 0.007961034 0.1522934 0.02071493 0.1434301 0.01716881 0.1479231 0.01234704 0.1360535 0.05899429 0.1282298 0.0844019 0.123577 0.06251293 0.4245075 0.9265977 0.4466516 0.9357835 0.4245074 0.9357835 0.1286125 0.2023019 0.1010712 0.1931164 0.1286125 0.1931164 0.1010712 0.1931164 0.07352977 0.2023016 0.07352977 0.1931163 0.4466516 0.9265977 0.449634 0.9357835 0.4466516 0.9357835 0.5411366 0.9155978 0.5548712 0.9247831 0.5411367 0.9247834 0.1282298 0.0844019 0.1020137 0.09187269 0.1021029 0.08445197 0.1023678 0.06344956 0.1221608 0.05621325 0.123577 0.06251293 0.139571 0.02124476 0.1369493 0.01433765 0.1434301 0.01716881 0.06751406 8.04474e-4 0.05789202 0.01086807 0.05387437 0.006297409 0.1334255 0.0527479 0.1427766 0.05496656 0.1360535 0.05899429 0.1359398 0.01979029 0.1029926 0.01307231 0.1369493 0.01433765 0.1032041 4.88464e-4 0.1377221 0.007961034 0.1031009 0.006463944 0.1459411 0.02213335 0.139571 0.02124476 0.1434301 0.01716881 0.08117532 0.06195604 0.07155132 0.05187094 0.08278739 0.05568909 0.1562597 0.1844575 0.1286125 0.1931164 0.1276409 0.1844576 0.08117532 0.06195604 0.1021029 0.08445197 0.07595032 0.08376377 0.1386654 0.04879873 0.1459805 0.04982274 0.1427766 0.05496656 0.06884676 0.01318633 0.1031009 0.006463944 0.1029926 0.01307231 0.4541368 0.9265977 0.4887897 0.9357835 0.4541367 0.9357835 0.1390759 0.1680715 0.1298903 0.1608373 0.1390759 0.1608373 0.149798 0.1758696 0.1562597 0.1666837 0.1562597 0.1758696 0.6214771 0.9247831 0.6316491 0.9155975 0.6316492 0.9247834 0.07595032 0.08376377 0.1020137 0.09187269 0.07465165 0.0912249 0.1023678 0.06344956 0.08278739 0.05568909 0.1024522 0.05688887 0.05961465 0.0207507 0.0660178 0.02002781 0.06499302 0.02227306 0.1386755 0.00206077 0.1479231 0.01234704 0.1377221 0.007961034 0.06636029 0.04771524 0.05894839 0.04857367 0.06446784 0.04335635 0.06967717 0.01867198 0.1029926 0.01307231 0.1029018 0.01896369 0.07450091 0.1844576 0.1010712 0.1931164 0.07352977 0.1931163 0.3649246 0.3329192 0.3186025 0.3452491 0.3186025 0.3329197 0.9182865 0.36029 0.883715 0.3694932 0.883598 0.36029 0.2725553 0.2944474 0.295579 0.2856099 0.295579 0.2944474 0.9060957 0.9410116 0.9425108 0.9521344 0.9060957 0.9521344 0.2725553 0.2944474 0.1882315 0.3205384 0.1882315 0.2944475 0.3186025 0.3329197 0.3649247 0.3205381 0.3649246 0.3329192 0.06104779 0.9072378 0.1485259 0.9326536 0.06104815 0.9326534 0.9201009 0.7871531 0.9450165 0.7608169 0.9450165 0.8029695 0.7194603 0.8119004 0.8702774 0.7697482 0.8702774 0.8119004 0.2090855 0.9228498 0.1669332 0.9326535 0.166933 0.9072378 0.1882315 0.252813 0.1792764 0.28561 0.1792763 0.2528129 0.05301833 0.28561 0.04406833 0.2528129 0.05301839 0.2528129 0.1882315 0.2944475 0.2725553 0.2856099 0.2725553 0.2944474 0.9450164 0.6056721 0.9201009 0.5964685 0.9450165 0.5964685 0.3649247 0.2052192 0.3186024 0.2140727 0.3186024 0.2052192 0.3186024 0.2140727 0.3649246 0.252813 0.3186024 0.2528129 0.2725553 0.2140727 0.295579 0.205219 0.295579 0.2140727 0.2725554 4.88297e-4 0.1882316 0.2052192 0.1882315 4.88337e-4 0.2725553 0.3329195 0.1882315 0.3205384 0.2725553 0.3205384 0.5055453 0.2944943 0.4695122 0.3205853 0.4695124 0.2944943 0.7194604 0.769748 0.867367 0.7610166 0.8702774 0.7697482 0.0622676 0.01583838 0.06827884 0.006764054 0.06884676 0.01318633 0.05183398 0.06548821 0.06873148 0.05807965 0.05513036 0.07444918 0.05326932 0.01916384 0.0622676 0.01583838 0.05961465 0.0207507 0.4193832 0.9265977 0.4245074 0.9357835 0.4193831 0.9357835 0.5530717 0.9357835 0.558196 0.9265977 0.558196 0.9357835 0.3899179 0.9247831 0.3797456 0.9155975 0.3899179 0.9155975 0.1479231 0.01234704 0.1582064 0.01933556 0.1522934 0.02071493 0.1390759 0.1680715 0.1298903 0.1753889 0.1252617 0.1680715 0.5775492 0.9357835 0.5978327 0.9265977 0.5978327 0.9357831 0.456524 0.9247831 0.4702587 0.9155978 0.4702587 0.9247834 0.05506855 0.08756864 0.0458827 0.09480309 0.04588252 0.08756864 0.0523439 0.1758695 0.04588282 0.1666837 0.05234396 0.1666837 0.0660178 0.02002781 0.06884676 0.01318633 0.06967717 0.01867198 0.1334255 0.0527479 0.123577 0.06251293 0.1221608 0.05621325 0.2725553 0.3205384 0.295579 0.2944474 0.2955789 0.3205384 0.4756165 0.4419285 0.4326246 0.6419227 0.4326246 0.4419285 0.1582064 0.01933556 0.1526682 0.06678771 0.1522934 0.02071493 1.918286 0.3786976 1.900266 0.5925588 1.918287 0.592559 1.918286 0.3786976 1.892347 0.5849624 1.900266 0.5925588 1.918286 0.3786976 1.884066 0.3786978 1.892347 0.5849624 1.918286 0.3694939 1.884066 0.3786978 1.918286 0.3786976 1.045883 0.2990664 1.156644 0.3412187 1.156644 0.2990664 1.957133 0.3386409 1.940316 0.5525014 1.957133 0.5525013 1.957133 0.3386409 1.932278 0.5449053 1.940316 0.5525014 1.957133 0.3386409 1.920751 0.3386411 1.932278 0.5449053 1.460565 0.2528128 1.373903 0.2140727 1.373903 0.2528129 1.463422 0.1205881 1.428085 0.1316481 1.463422 0.1316481 1.272555 0.2528129 1.188232 0.28561 1.272555 0.2856099 1.945016 0.6148759 1.920101 0.7424094 1.945016 0.7424094 1.475616 0.4326248 1.432625 0.4419285 1.475616 0.4419285 1.900266 4.88286e-4 1.918287 0.2143492 1.918286 4.88286e-4 1.892347 0.008084595 1.918287 0.2143492 1.900266 4.88286e-4 1.892347 0.008084595 1.884065 0.2143492 1.918287 0.2143492 1.940316 4.88303e-4 1.957133 0.2143483 1.957133 4.88287e-4 1.932278 0.008084475 1.957133 0.2143483 1.940316 4.88303e-4 1.932278 0.008084475 1.920752 0.2143484 1.957133 0.2143483 1.179276 0.28561 1.053018 0.2528129 1.053018 0.28561 1.935713 0.8029695 1.920101 0.7871531 1.924004 0.7990155 1.945016 0.8029695 1.920101 0.7871531 1.935713 0.8029695 1.920101 0.570132 1.935713 0.5543157 1.924004 0.5582697 1.920101 0.570132 1.945016 0.5543156 1.935713 0.5543157 1.044068 0.3329567 1.000488 0.3205851 1.000488 0.3329567 1.295579 0.252813 1.272555 0.2856099 1.295579 0.2856099 1.193269 0.907238 1.209085 0.9228498 1.205131 0.9111408 1.166933 0.9072378 1.209085 0.9228498 1.193269 0.907238 1.000488 0.92285 1.016304 0.907238 1.004442 0.9111411 1.000488 0.92285 1.042641 0.9072379 1.016304 0.907238 1.728519 0.4506204 1.718715 0.4958242 1.728519 0.4958242 1.710524 0.4326251 1.718715 0.4958242 1.728519 0.4506204 1.710524 0.4326251 1.728519 0.4506204 1.725179 0.4359653 1.626433 0.4419283 1.432625 0.6419227 1.718715 0.4958242 1.272555 0.2528129 1.295579 0.2140727 1.272555 0.2140727 1.718715 0.4958242 1.432625 0.6419227 1.718715 0.6065858 1.432625 0.6419227 1.626433 0.4419283 1.475616 0.4419285 1.718715 0.6065858 1.432625 0.6419227 1.710385 0.6419227 1.731102 0.7581059 1.867367 0.7610166 1.858635 0.7581059 1.867367 0.7610166 1.731102 0.7581059 1.722371 0.7610161 1.870142 0.5603047 1.733877 0.5573942 1.742609 0.5603047 1.733877 0.5573942 1.870142 0.5603047 1.878873 0.5573942 1.719089 0.9275556 1.721999 0.831346 1.719089 0.8400775 1.721999 0.831346 1.719089 0.9275556 1.721999 0.9362868 1.057524 0.2874242 1.153734 0.2903351 1.145002 0.2874242 1.153734 0.2903351 1.057524 0.2874242 1.048793 0.2903351 1.14918 0.07562226 1.136054 0.05899429 1.141682 0.0840274 1.142777 0.05496656 1.152668 0.06678771 1.14598 0.04982274 1.454137 0.9357835 1.449634 0.9265977 1.449634 0.9357835 1.577549 0.9265977 1.565234 0.9357835 1.577549 0.9357835 1.456524 0.9155978 1.444498 0.9247831 1.456524 0.9247831 1.40003 0.9357835 1.379746 0.9265977 1.379746 0.9357835 1.047357 0.01762789 1.051834 0.06548821 1.053269 0.01916384 1.152293 0.02071493 1.14598 0.04982274 1.152668 0.06678771 1.071551 0.05187094 1.06206 0.053842 1.068732 0.05807965 1.14918 0.07562226 1.15839 0.07515925 1.152668 0.06678771 1.15839 0.07515925 1.14918 0.07562226 1.153132 0.08474558 1.103204 4.88464e-4 1.068279 0.006764054 1.103101 0.006463944 1.141682 0.0840274 1.129347 0.09187269 1.153132 0.08474558 1.127641 0.1844576 1.101071 0.1931164 1.128612 0.1931164 1.129347 0.09187269 1.141682 0.0840274 1.12823 0.0844019 1.141682 0.0840274 1.153132 0.08474558 1.14918 0.07562226 1.15626 0.1758696 1.127641 0.1844576 1.15626 0.1844575 1.127641 0.1844576 1.15626 0.1758696 1.149798 0.1758696 1.064468 0.04335635 1.059615 0.0207507 1.058948 0.04857367 1.123577 0.06251293 1.102103 0.08445197 1.12823 0.0844019 1.068732 0.05807965 1.05513 0.07444918 1.062461 0.08306509 1.051834 0.06548821 1.06206 0.053842 1.058948 0.04857367 1.527945 0.9265979 1.523443 0.9357835 1.527945 0.9357835 1.541137 0.9247834 1.505697 0.9155978 1.505697 0.9247834 1.523443 0.9265977 1.48879 0.9357835 1.523443 0.9357835 1.045883 0.2023016 1.07353 0.1931163 1.045883 0.193116 1.444498 0.9155978 1.389918 0.9247831 1.444498 0.9247831 1.566898 0.9247831 1.554871 0.9155978 1.554871 0.9247831 1.053269 0.01916384 1.058948 0.04857367 1.059615 0.0207507 1.140609 0.0445531 1.145941 0.02213335 1.14054 0.0235123 1.05513 0.07444918 1.045888 0.07377058 1.050949 0.0835188 1.045888 0.07377058 1.05513 0.07444918 1.051834 0.06548821 1.062461 0.08306509 1.050949 0.0835188 1.074652 0.0912249 1.045883 0.1844576 1.07353 0.1931163 1.074501 0.1844576 1.074652 0.0912249 1.07595 0.08376377 1.062461 0.08306509 1.062461 0.08306509 1.05513 0.07444918 1.050949 0.0835188 1.045883 0.1758695 1.074501 0.1844576 1.052344 0.1758695 1.074501 0.1844576 1.045883 0.1758695 1.045883 0.1844576 1.295579 0.205219 1.318602 0.2140727 1.318602 0.2052192 1.318602 0.3329197 1.295579 0.3452492 1.318602 0.3452491 1.884241 0.9410114 1.862386 0.952134 1.884241 0.9521344 1.920263 0.223552 1.957133 0.2327558 1.957133 0.2235522 1.364925 0.2944475 1.318602 0.3205383 1.364925 0.3205381 1.920101 0.2327558 1.957133 0.3202335 1.957133 0.2327558 1.157729 0.907238 1.166933 0.9326535 1.166933 0.9072378 1.000488 0.3452001 1.044068 0.3329567 1.000488 0.3329567 1.042641 0.9326536 1.000488 0.92285 1.000488 0.9326536 1.728519 0.6419227 1.718715 0.6065858 1.710385 0.6419227 1.053018 0.2528129 1.179276 0.2140728 1.053018 0.2140728 1.051845 0.9326536 1.042641 0.9072379 1.042641 0.9326536 1.000488 0.28561 1.044068 0.2944945 1.044068 0.28561 1.373903 0.28561 1.364925 0.252813 1.364925 0.28561 1.373903 0.28561 1.460565 0.2528128 1.373903 0.2528129 1.469512 0.2528128 1.460565 0.2856102 1.469512 0.2856102 1.460565 0.2140728 1.469512 0.2528128 1.469512 0.2140727 1.000488 0.2140725 1.044068 0.2051816 1.000488 0.2051817 1.505545 0.2856101 1.469512 0.2944943 1.505545 0.2944943 1.156644 0.2990664 1.048793 0.2903351 1.045883 0.2990664 1.553072 0.9265979 1.530928 0.9357835 1.553072 0.9357835 1.565234 0.9265977 1.558196 0.9357835 1.565234 0.9357835 1.530928 0.9265979 1.527945 0.9357835 1.530928 0.9357835 1.057892 0.01086807 1.047357 0.01762789 1.053269 0.01916384 1.045883 0.09480309 1.055068 0.1021202 1.059697 0.09480309 1.068732 0.05807965 1.07595 0.08376377 1.081175 0.06195604 1.128612 0.1931164 1.15626 0.2023016 1.15626 0.1931163 1.419383 0.9357835 1.412345 0.9265977 1.412345 0.9357835 1.621477 0.9247831 1.566897 0.9155978 1.566898 0.9247831 1.412345 0.9357835 1.40003 0.9265977 1.40003 0.9357835 1.505697 0.9155978 1.470259 0.9247834 1.505697 0.9247834 1.295579 4.88289e-4 1.272555 0.2052192 1.295579 0.205219 1.318602 0.2944474 1.295579 0.3205384 1.318602 0.3205383 1.272555 0.3329195 1.295579 0.3452492 1.295579 0.3329195 1.318602 0.3205383 1.295579 0.3329195 1.318602 0.3329197 1.272555 0.3205384 1.295579 0.3329195 1.295579 0.3205384 1.945016 0.5964685 1.920101 0.570132 1.920101 0.5964685 1.906096 0.9521344 1.884241 0.9410114 1.884241 0.9521344 1.791454 0.9521344 1.862386 0.9410116 1.791454 0.9410114 1.469512 0.3452002 1.505545 0.3329566 1.469512 0.3329566 1.884065 0.2143492 1.918286 0.2235528 1.918287 0.2143492 1.883715 0.2235527 1.918287 0.2327569 1.918286 0.2235528 1.957133 0.3294374 1.920751 0.3386411 1.957133 0.3386409 1.957133 0.3202335 1.920264 0.3294375 1.957133 0.3294374 1.272555 0.3452491 1.188232 0.3329193 1.188232 0.3452492 1.945016 0.7608169 1.920101 0.7516131 1.920101 0.7608169 1.08002 0.04160183 1.123011 0.05257523 1.123011 0.04160183 1.945016 0.6148759 1.920101 0.6056721 1.920101 0.6148759 1.920752 0.2143484 1.957133 0.2235522 1.957133 0.2143483 1.061048 0.9326534 1.051844 0.9072378 1.051845 0.9326536 1.148526 0.9326536 1.157729 0.907238 1.148526 0.9072379 1.000488 0.3205851 1.044068 0.2944945 1.000488 0.2944943 1.044068 6.73867e-4 1.000488 0.2051817 1.044068 0.2051816 1.364925 0.252813 1.373903 0.2140727 1.364925 0.2140727 1.730731 0.9391972 1.944592 0.8284353 1.730731 0.8284351 1.000488 0.2528129 1.044068 0.28561 1.044068 0.2528129 1.945016 0.7516131 1.920101 0.7424094 1.920101 0.7516131 1.883598 0.2327569 1.918286 0.36029 1.918287 0.2327569 1.710524 0.4326251 1.626433 0.4419283 1.718715 0.4958242 1.505545 0.3329566 1.469512 0.3205853 1.469512 0.3329566 1.044068 0.2528129 1.053018 0.2140728 1.044068 0.2140728 1.179276 0.2140728 1.188231 0.252813 1.188232 0.2140728 1.318602 0.2856103 1.295579 0.2944474 1.318602 0.2944474 1.318602 0.2528129 1.295579 0.2856099 1.318602 0.2856103 1.364925 0.2944475 1.318602 0.2856103 1.318602 0.2944474 1.364925 0.252813 1.318602 0.2856103 1.364925 0.28561 1.272555 0.2140727 1.188232 0.2052192 1.188232 0.2140728 1.295579 0.2140727 1.318602 0.2528129 1.318602 0.2140727 1.272555 0.2140727 1.188231 0.252813 1.272555 0.2528129 1.318602 0.2052192 1.295579 4.88289e-4 1.295579 0.205219 1.364925 0.2052192 1.318603 4.88513e-4 1.318602 0.2052192 1.505545 0.2528129 1.469512 0.2140727 1.469512 0.2528128 1.505545 0.2140728 1.469512 0.2051753 1.469512 0.2140727 1.469512 5.12323e-4 1.505545 0.2051752 1.505545 5.12315e-4 1.505545 0.2528129 1.469512 0.2856102 1.505545 0.2856101 1.730967 0.3348015 1.881784 0.5486628 1.881784 0.3348016 1.000488 0.2528129 1.044068 0.2140728 1.000488 0.2140725 1.730967 0.5486626 1.878873 0.5573942 1.881784 0.5486628 1.721999 0.831346 1.730731 0.9391972 1.730731 0.8284351 1.14343 0.01716881 1.137722 0.007961034 1.136949 0.01433765 1.152668 0.06678771 1.136054 0.05899429 1.14918 0.07562226 1.136949 0.01433765 1.103101 0.006463944 1.102993 0.01307231 1.152293 0.02071493 1.14343 0.01716881 1.145941 0.02213335 1.12823 0.0844019 1.136054 0.05899429 1.123577 0.06251293 1.446652 0.9357835 1.424507 0.9265977 1.424507 0.9357835 1.101071 0.1931164 1.128612 0.2023019 1.128612 0.1931164 1.07353 0.2023016 1.101071 0.1931164 1.07353 0.1931163 1.449634 0.9357835 1.446652 0.9265977 1.446652 0.9357835 1.554871 0.9247831 1.541136 0.9155978 1.541137 0.9247834 1.12823 0.0844019 1.102014 0.09187269 1.129347 0.09187269 1.102368 0.06344956 1.122161 0.05621325 1.102452 0.05688887 1.139571 0.02124476 1.136949 0.01433765 1.13594 0.01979029 1.067514 8.04474e-4 1.057892 0.01086807 1.068279 0.006764054 1.133425 0.0527479 1.142777 0.05496656 1.138665 0.04879873 1.13594 0.01979029 1.102993 0.01307231 1.102902 0.01896369 1.137722 0.007961034 1.103204 4.88464e-4 1.103101 0.006463944 1.145941 0.02213335 1.139571 0.02124476 1.14054 0.0235123 1.071551 0.05187094 1.081175 0.06195604 1.082787 0.05568909 1.15626 0.1844575 1.128612 0.1931164 1.15626 0.1931163 1.081175 0.06195604 1.102103 0.08445197 1.102368 0.06344956 1.138665 0.04879873 1.14598 0.04982274 1.140609 0.0445531 1.068847 0.01318633 1.103101 0.006463944 1.068279 0.006764054 1.48879 0.9357835 1.454137 0.9265977 1.454137 0.9357835 1.12989 0.1608373 1.139076 0.1680715 1.139076 0.1608373 1.149798 0.1758696 1.15626 0.1666837 1.149798 0.1666839 1.621477 0.9247831 1.631649 0.9155975 1.621477 0.9155975 1.07595 0.08376377 1.102014 0.09187269 1.102103 0.08445197 1.102368 0.06344956 1.082787 0.05568909 1.081175 0.06195604 1.059615 0.0207507 1.066018 0.02002781 1.062268 0.01583838 1.138676 0.00206077 1.147923 0.01234704 1.152043 0.007921338 1.06636 0.04771524 1.058948 0.04857367 1.06206 0.053842 1.069677 0.01867198 1.102993 0.01307231 1.068847 0.01318633 1.074501 0.1844576 1.101071 0.1931164 1.101071 0.1844576 1.364925 0.3329192 1.318602 0.3452491 1.364925 0.3452492 1.918286 0.36029 1.883715 0.3694932 1.918286 0.3694939 1.295579 0.2856099 1.272555 0.2944474 1.295579 0.2944474 1.906096 0.9410116 1.942511 0.9521344 1.942511 0.9410114 1.188232 0.3205384 1.272555 0.2944474 1.188232 0.2944475 1.318602 0.3329197 1.364925 0.3205381 1.318602 0.3205383 1.061048 0.9072378 1.148526 0.9326536 1.148526 0.9072379 1.920101 0.7871531 1.945016 0.7608169 1.920101 0.7608169 1.870277 0.7697482 1.71946 0.8119004 1.870277 0.8119004 1.209085 0.9228498 1.166933 0.9326535 1.209086 0.9326535 1.188231 0.252813 1.179276 0.28561 1.188232 0.28561 1.053018 0.28561 1.044068 0.2528129 1.044068 0.28561 1.272555 0.2856099 1.188232 0.2944475 1.272555 0.2944474 1.945016 0.6056721 1.920101 0.5964685 1.920101 0.6056721 1.364925 0.2052192 1.318602 0.2140727 1.364925 0.2140727 1.318602 0.2140727 1.364925 0.252813 1.364925 0.2140727 1.272555 0.2140727 1.295579 0.205219 1.272555 0.2052192 1.272555 4.88297e-4 1.188232 0.2052192 1.272555 0.2052192 1.272555 0.3329195 1.188232 0.3205384 1.188232 0.3329193 1.469512 0.3205853 1.505545 0.2944943 1.469512 0.2944943 1.867367 0.7610166 1.71946 0.769748 1.870277 0.7697482 1.062268 0.01583838 1.068279 0.006764054 1.057892 0.01086807 1.068732 0.05807965 1.051834 0.06548821 1.05513 0.07444918 1.053269 0.01916384 1.062268 0.01583838 1.057892 0.01086807 1.424507 0.9357835 1.419383 0.9265977 1.419383 0.9357835 1.558196 0.9265977 1.553072 0.9357835 1.558196 0.9357835 1.389918 0.9247831 1.379746 0.9155975 1.379746 0.9247834 1.147923 0.01234704 1.158206 0.01933556 1.152043 0.007921338 1.139076 0.1680715 1.12989 0.1753889 1.139076 0.1753889 1.597833 0.9265977 1.577549 0.9357835 1.597833 0.9357831 1.470259 0.9155978 1.456524 0.9247831 1.470259 0.9247834 1.045883 0.09480309 1.055069 0.08756864 1.045883 0.08756864 1.052344 0.1758695 1.045883 0.1666837 1.045883 0.1758695 1.066018 0.02002781 1.068847 0.01318633 1.062268 0.01583838 1.123577 0.06251293 1.133425 0.0527479 1.122161 0.05621325 1.295579 0.2944474 1.272555 0.3205384 1.295579 0.3205384 1.475616 0.4419285 1.432625 0.4419285 1.432625 0.6419227 1.158206 0.01933556 1.152668 0.06678771 1.15839 0.07515925 1.918286 0.3786976 1.900266 0.5925588 1.918287 0.592559 1.918286 0.3786976 1.892347 0.5849624 1.900266 0.5925588 1.918286 0.3786976 1.884066 0.3786978 1.892347 0.5849624 1.918286 0.3694939 1.884066 0.3786978 1.918286 0.3786976 1.045883 0.2990664 1.156644 0.3412187 1.156644 0.2990664 1.957133 0.3386409 1.940316 0.5525014 1.957133 0.5525013 1.957133 0.3386409 1.932278 0.5449053 1.940316 0.5525014 1.957133 0.3386409 1.920751 0.3386411 1.932278 0.5449053 1.460565 0.2528128 1.373903 0.2140727 1.373903 0.2528129 1.463422 0.1205881 1.428085 0.1316481 1.463422 0.1316481 1.272555 0.2528129 1.188232 0.28561 1.272555 0.2856099 1.945016 0.6148759 1.920101 0.7424094 1.945016 0.7424094 1.475616 0.4326248 1.432625 0.4419285 1.475616 0.4419285 1.900266 4.88286e-4 1.918287 0.2143492 1.918286 4.88286e-4 1.892347 0.008084595 1.918287 0.2143492 1.900266 4.88286e-4 1.892347 0.008084595 1.884065 0.2143492 1.918287 0.2143492 1.940316 4.88303e-4 1.957133 0.2143483 1.957133 4.88287e-4 1.932278 0.008084475 1.957133 0.2143483 1.940316 4.88303e-4 1.932278 0.008084475 1.920752 0.2143484 1.957133 0.2143483 1.179276 0.28561 1.053018 0.2528129 1.053018 0.28561 1.935713 0.8029695 1.920101 0.7871531 1.924004 0.7990155 1.945016 0.8029695 1.920101 0.7871531 1.935713 0.8029695 1.920101 0.570132 1.935713 0.5543157 1.924004 0.5582697 1.920101 0.570132 1.945016 0.5543156 1.935713 0.5543157 1.044068 0.3329567 1.000488 0.3205851 1.000488 0.3329567 1.295579 0.252813 1.272555 0.2856099 1.295579 0.2856099 1.193269 0.907238 1.209085 0.9228498 1.205131 0.9111408 1.166933 0.9072378 1.209085 0.9228498 1.193269 0.907238 1.000488 0.92285 1.016304 0.907238 1.004442 0.9111411 1.000488 0.92285 1.042641 0.9072379 1.016304 0.907238 1.728519 0.4506204 1.718715 0.4958242 1.728519 0.4958242 1.710524 0.4326251 1.718715 0.4958242 1.728519 0.4506204 1.710524 0.4326251 1.728519 0.4506204 1.725179 0.4359653 1.626433 0.4419283 1.432625 0.6419227 1.718715 0.4958242 1.272555 0.2528129 1.295579 0.2140727 1.272555 0.2140727 1.718715 0.4958242 1.432625 0.6419227 1.718715 0.6065858 1.432625 0.6419227 1.626433 0.4419283 1.475616 0.4419285 1.718715 0.6065858 1.432625 0.6419227 1.710385 0.6419227 1.731102 0.7581059 1.867367 0.7610166 1.858635 0.7581059 1.867367 0.7610166 1.731102 0.7581059 1.722371 0.7610161 1.870142 0.5603047 1.733877 0.5573942 1.742609 0.5603047 1.733877 0.5573942 1.870142 0.5603047 1.878873 0.5573942 1.719089 0.9275556 1.721999 0.831346 1.719089 0.8400775 1.721999 0.831346 1.719089 0.9275556 1.721999 0.9362868 1.057524 0.2874242 1.153734 0.2903351 1.145002 0.2874242 1.153734 0.2903351 1.057524 0.2874242 1.048793 0.2903351 1.14918 0.07562226 1.136054 0.05899429 1.141682 0.0840274 1.142777 0.05496656 1.152668 0.06678771 1.14598 0.04982274 1.454137 0.9357835 1.449634 0.9265977 1.449634 0.9357835 1.577549 0.9265977 1.565234 0.9357835 1.577549 0.9357835 1.456524 0.9155978 1.444498 0.9247831 1.456524 0.9247831 1.40003 0.9357835 1.379746 0.9265977 1.379746 0.9357835 1.047357 0.01762789 1.051834 0.06548821 1.053269 0.01916384 1.152293 0.02071493 1.14598 0.04982274 1.152668 0.06678771 1.071551 0.05187094 1.06206 0.053842 1.068732 0.05807965 1.14918 0.07562226 1.15839 0.07515925 1.152668 0.06678771 1.15839 0.07515925 1.14918 0.07562226 1.153132 0.08474558 1.103204 4.88464e-4 1.068279 0.006764054 1.103101 0.006463944 1.141682 0.0840274 1.129347 0.09187269 1.153132 0.08474558 1.127641 0.1844576 1.101071 0.1931164 1.128612 0.1931164 1.129347 0.09187269 1.141682 0.0840274 1.12823 0.0844019 1.141682 0.0840274 1.153132 0.08474558 1.14918 0.07562226 1.15626 0.1758696 1.127641 0.1844576 1.15626 0.1844575 1.127641 0.1844576 1.15626 0.1758696 1.149798 0.1758696 1.064468 0.04335635 1.059615 0.0207507 1.058948 0.04857367 1.123577 0.06251293 1.102103 0.08445197 1.12823 0.0844019 1.068732 0.05807965 1.05513 0.07444918 1.062461 0.08306509 1.051834 0.06548821 1.06206 0.053842 1.058948 0.04857367 1.527945 0.9265979 1.523443 0.9357835 1.527945 0.9357835 1.541137 0.9247834 1.505697 0.9155978 1.505697 0.9247834 1.523443 0.9265977 1.48879 0.9357835 1.523443 0.9357835 1.045883 0.2023016 1.07353 0.1931163 1.045883 0.193116 1.444498 0.9155978 1.389918 0.9247831 1.444498 0.9247831 1.566898 0.9247831 1.554871 0.9155978 1.554871 0.9247831 1.053269 0.01916384 1.058948 0.04857367 1.059615 0.0207507 1.140609 0.0445531 1.145941 0.02213335 1.14054 0.0235123 1.05513 0.07444918 1.045888 0.07377058 1.050949 0.0835188 1.045888 0.07377058 1.05513 0.07444918 1.051834 0.06548821 1.062461 0.08306509 1.050949 0.0835188 1.074652 0.0912249 1.045883 0.1844576 1.07353 0.1931163 1.074501 0.1844576 1.074652 0.0912249 1.07595 0.08376377 1.062461 0.08306509 1.062461 0.08306509 1.05513 0.07444918 1.050949 0.0835188 1.045883 0.1758695 1.074501 0.1844576 1.052344 0.1758695 1.074501 0.1844576 1.045883 0.1758695 1.045883 0.1844576 1.295579 0.205219 1.318602 0.2140727 1.318602 0.2052192 1.318602 0.3329197 1.295579 0.3452492 1.318602 0.3452491 1.884241 0.9410114 1.862386 0.952134 1.884241 0.9521344 1.920263 0.223552 1.957133 0.2327558 1.957133 0.2235522 1.364925 0.2944475 1.318602 0.3205383 1.364925 0.3205381 1.920101 0.2327558 1.957133 0.3202335 1.957133 0.2327558 1.157729 0.907238 1.166933 0.9326535 1.166933 0.9072378 1.000488 0.3452001 1.044068 0.3329567 1.000488 0.3329567 1.042641 0.9326536 1.000488 0.92285 1.000488 0.9326536 1.728519 0.6419227 1.718715 0.6065858 1.710385 0.6419227 1.053018 0.2528129 1.179276 0.2140728 1.053018 0.2140728 1.051845 0.9326536 1.042641 0.9072379 1.042641 0.9326536 1.000488 0.28561 1.044068 0.2944945 1.044068 0.28561 1.373903 0.28561 1.364925 0.252813 1.364925 0.28561 1.373903 0.28561 1.460565 0.2528128 1.373903 0.2528129 1.469512 0.2528128 1.460565 0.2856102 1.469512 0.2856102 1.460565 0.2140728 1.469512 0.2528128 1.469512 0.2140727 1.000488 0.2140725 1.044068 0.2051816 1.000488 0.2051817 1.505545 0.2856101 1.469512 0.2944943 1.505545 0.2944943 1.153734 0.2903351 1.045883 0.2990664 1.156644 0.2990664 1.553072 0.9265979 1.530928 0.9357835 1.553072 0.9357835 1.565234 0.9265977 1.558196 0.9357835 1.565234 0.9357835 1.530928 0.9265979 1.527945 0.9357835 1.530928 0.9357835 1.057892 0.01086807 1.047357 0.01762789 1.053269 0.01916384 1.045883 0.09480309 1.055068 0.1021202 1.059697 0.09480309 1.068732 0.05807965 1.07595 0.08376377 1.081175 0.06195604 1.128612 0.1931164 1.15626 0.2023016 1.15626 0.1931163 1.419383 0.9357835 1.412345 0.9265977 1.412345 0.9357835 1.621477 0.9247831 1.566897 0.9155978 1.566898 0.9247831 1.412345 0.9357835 1.40003 0.9265977 1.40003 0.9357835 1.505697 0.9155978 1.470259 0.9247834 1.505697 0.9247834 1.295579 4.88289e-4 1.272555 0.2052192 1.295579 0.205219 1.318602 0.2944474 1.295579 0.3205384 1.318602 0.3205383 1.272555 0.3329195 1.295579 0.3452492 1.295579 0.3329195 1.318602 0.3205383 1.295579 0.3329195 1.318602 0.3329197 1.272555 0.3205384 1.295579 0.3329195 1.295579 0.3205384 1.945016 0.5964685 1.920101 0.570132 1.920101 0.5964685 1.906096 0.9521344 1.884241 0.9410114 1.884241 0.9521344 1.791454 0.9521344 1.862386 0.9410116 1.791454 0.9410114 1.469512 0.3452002 1.505545 0.3329566 1.469512 0.3329566 1.884065 0.2143492 1.918286 0.2235528 1.918287 0.2143492 1.883715 0.2235527 1.918287 0.2327569 1.918286 0.2235528 1.957133 0.3294374 1.920751 0.3386411 1.957133 0.3386409 1.957133 0.3202335 1.920264 0.3294375 1.957133 0.3294374 1.272555 0.3452491 1.188232 0.3329193 1.188232 0.3452492 1.945016 0.7608169 1.920101 0.7516131 1.920101 0.7608169 1.08002 0.04160183 1.123011 0.05257523 1.123011 0.04160183 1.945016 0.6148759 1.920101 0.6056721 1.920101 0.6148759 1.920752 0.2143484 1.957133 0.2235522 1.957133 0.2143483 1.061048 0.9326534 1.051844 0.9072378 1.051845 0.9326536 1.148526 0.9326536 1.157729 0.907238 1.148526 0.9072379 1.000488 0.3205851 1.044068 0.2944945 1.000488 0.2944943 1.044068 6.73867e-4 1.000488 0.2051817 1.044068 0.2051816 1.364925 0.252813 1.373903 0.2140727 1.364925 0.2140727 1.730731 0.9391972 1.944592 0.8284353 1.730731 0.8284351 1.000488 0.2528129 1.044068 0.28561 1.044068 0.2528129 1.945016 0.7516131 1.920101 0.7424094 1.920101 0.7516131 1.883598 0.2327569 1.918286 0.36029 1.918287 0.2327569 1.710524 0.4326251 1.626433 0.4419283 1.718715 0.4958242 1.505545 0.3329566 1.469512 0.3205853 1.469512 0.3329566 1.044068 0.2528129 1.053018 0.2140728 1.044068 0.2140728 1.179276 0.2140728 1.188231 0.252813 1.188232 0.2140728 1.318602 0.2856103 1.295579 0.2944474 1.318602 0.2944474 1.318602 0.2528129 1.295579 0.2856099 1.318602 0.2856103 1.364925 0.2944475 1.318602 0.2856103 1.318602 0.2944474 1.364925 0.252813 1.318602 0.2856103 1.364925 0.28561 1.272555 0.2140727 1.188232 0.2052192 1.188232 0.2140728 1.295579 0.2140727 1.318602 0.2528129 1.318602 0.2140727 1.272555 0.2140727 1.188231 0.252813 1.272555 0.2528129 1.318602 0.2052192 1.295579 4.88289e-4 1.295579 0.205219 1.364925 0.2052192 1.318603 4.88513e-4 1.318602 0.2052192 1.505545 0.2528129 1.469512 0.2140727 1.469512 0.2528128 1.505545 0.2140728 1.469512 0.2051753 1.469512 0.2140727 1.469512 5.12323e-4 1.505545 0.2051752 1.505545 5.12315e-4 1.505545 0.2528129 1.469512 0.2856102 1.505545 0.2856101 1.730967 0.3348015 1.881784 0.5486628 1.881784 0.3348016 1.000488 0.2528129 1.044068 0.2140728 1.000488 0.2140725 1.730967 0.5486626 1.878873 0.5573942 1.881784 0.5486628 1.721999 0.831346 1.730731 0.9391972 1.730731 0.8284351 1.14343 0.01716881 1.137722 0.007961034 1.136949 0.01433765 1.152668 0.06678771 1.136054 0.05899429 1.14918 0.07562226 1.136949 0.01433765 1.103101 0.006463944 1.102993 0.01307231 1.152293 0.02071493 1.14343 0.01716881 1.145941 0.02213335 1.12823 0.0844019 1.136054 0.05899429 1.123577 0.06251293 1.446652 0.9357835 1.424507 0.9265977 1.424507 0.9357835 1.101071 0.1931164 1.128612 0.2023019 1.128612 0.1931164 1.07353 0.2023016 1.101071 0.1931164 1.07353 0.1931163 1.449634 0.9357835 1.446652 0.9265977 1.446652 0.9357835 1.554871 0.9247831 1.541136 0.9155978 1.541137 0.9247834 1.12823 0.0844019 1.102014 0.09187269 1.129347 0.09187269 1.102368 0.06344956 1.122161 0.05621325 1.102452 0.05688887 1.139571 0.02124476 1.136949 0.01433765 1.13594 0.01979029 1.067514 8.04474e-4 1.057892 0.01086807 1.068279 0.006764054 1.133425 0.0527479 1.142777 0.05496656 1.138665 0.04879873 1.13594 0.01979029 1.102993 0.01307231 1.102902 0.01896369 1.137722 0.007961034 1.103204 4.88464e-4 1.103101 0.006463944 1.145941 0.02213335 1.139571 0.02124476 1.14054 0.0235123 1.071551 0.05187094 1.081175 0.06195604 1.082787 0.05568909 1.15626 0.1844575 1.128612 0.1931164 1.15626 0.1931163 1.081175 0.06195604 1.102103 0.08445197 1.102368 0.06344956 1.138665 0.04879873 1.14598 0.04982274 1.140609 0.0445531 1.068847 0.01318633 1.103101 0.006463944 1.068279 0.006764054 1.48879 0.9357835 1.454137 0.9265977 1.454137 0.9357835 1.12989 0.1608373 1.139076 0.1680715 1.139076 0.1608373 1.149798 0.1758696 1.15626 0.1666837 1.149798 0.1666839 1.621477 0.9247831 1.631649 0.9155975 1.621477 0.9155975 1.07595 0.08376377 1.102014 0.09187269 1.102103 0.08445197 1.102368 0.06344956 1.082787 0.05568909 1.081175 0.06195604 1.059615 0.0207507 1.066018 0.02002781 1.062268 0.01583838 1.138676 0.00206077 1.147923 0.01234704 1.152043 0.007921338 1.06636 0.04771524 1.058948 0.04857367 1.06206 0.053842 1.069677 0.01867198 1.102993 0.01307231 1.068847 0.01318633 1.074501 0.1844576 1.101071 0.1931164 1.101071 0.1844576 1.364925 0.3329192 1.318602 0.3452491 1.364925 0.3452492 1.918286 0.36029 1.883715 0.3694932 1.918286 0.3694939 1.295579 0.2856099 1.272555 0.2944474 1.295579 0.2944474 1.906096 0.9410116 1.942511 0.9521344 1.942511 0.9410114 1.188232 0.3205384 1.272555 0.2944474 1.188232 0.2944475 1.318602 0.3329197 1.364925 0.3205381 1.318602 0.3205383 1.061048 0.9072378 1.148526 0.9326536 1.148526 0.9072379 1.920101 0.7871531 1.945016 0.7608169 1.920101 0.7608169 1.870277 0.7697482 1.71946 0.8119004 1.870277 0.8119004 1.209085 0.9228498 1.166933 0.9326535 1.209086 0.9326535 1.188231 0.252813 1.179276 0.28561 1.188232 0.28561 1.053018 0.28561 1.044068 0.2528129 1.044068 0.28561 1.272555 0.2856099 1.188232 0.2944475 1.272555 0.2944474 1.945016 0.6056721 1.920101 0.5964685 1.920101 0.6056721 1.364925 0.2052192 1.318602 0.2140727 1.364925 0.2140727 1.318602 0.2140727 1.364925 0.252813 1.364925 0.2140727 1.272555 0.2140727 1.295579 0.205219 1.272555 0.2052192 1.272555 4.88297e-4 1.188232 0.2052192 1.272555 0.2052192 1.272555 0.3329195 1.188232 0.3205384 1.188232 0.3329193 1.469512 0.3205853 1.505545 0.2944943 1.469512 0.2944943 1.867367 0.7610166 1.71946 0.769748 1.870277 0.7697482 1.062268 0.01583838 1.068279 0.006764054 1.057892 0.01086807 1.068732 0.05807965 1.051834 0.06548821 1.05513 0.07444918 1.053269 0.01916384 1.062268 0.01583838 1.057892 0.01086807 1.424507 0.9357835 1.419383 0.9265977 1.419383 0.9357835 1.558196 0.9265977 1.553072 0.9357835 1.558196 0.9357835 1.389918 0.9247831 1.379746 0.9155975 1.379746 0.9247834 1.147923 0.01234704 1.158206 0.01933556 1.152043 0.007921338 1.139076 0.1680715 1.12989 0.1753889 1.139076 0.1753889 1.597833 0.9265977 1.577549 0.9357835 1.597833 0.9357831 1.470259 0.9155978 1.456524 0.9247831 1.470259 0.9247834 1.045883 0.09480309 1.055069 0.08756864 1.045883 0.08756864 1.052344 0.1758695 1.045883 0.1666837 1.045883 0.1758695 1.066018 0.02002781 1.068847 0.01318633 1.062268 0.01583838 1.123577 0.06251293 1.133425 0.0527479 1.122161 0.05621325 1.295579 0.2944474 1.272555 0.3205384 1.295579 0.3205384 1.475616 0.4419285 1.432625 0.4419285 1.432625 0.6419227 1.158206 0.01933556 1.152668 0.06678771 1.15839 0.07515925 1.918286 0.3786976 1.918287 0.592559 1.900266 0.5925588 1.918286 0.3786976 1.900266 0.5925588 1.892347 0.5849624 1.918286 0.3786976 1.892347 0.5849624 1.884066 0.3786978 1.918286 0.3694939 1.884066 0.3786978 1.883715 0.3694932 1.156644 0.3412187 1.045883 0.2990664 1.156644 0.2990664 1.957133 0.3386409 1.957133 0.5525013 1.940316 0.5525014 1.957133 0.3386409 1.940316 0.5525014 1.932278 0.5449053 1.957133 0.3386409 1.932278 0.5449053 1.920751 0.3386411 1.460565 0.2528128 1.373903 0.2140727 1.460565 0.2140728 1.428085 0.1316481 1.463422 0.1205881 1.463422 0.1316481 1.272555 0.2528129 1.188232 0.28561 1.188231 0.252813 1.920101 0.7424094 1.945016 0.6148759 1.945016 0.7424094 1.432625 0.4419285 1.475616 0.4326248 1.475616 0.4419285 1.900266 4.88286e-4 1.918286 4.88286e-4 1.918287 0.2143492 1.892347 0.008084595 1.900266 4.88286e-4 1.918287 0.2143492 1.892347 0.008084595 1.918287 0.2143492 1.884065 0.2143492 1.940316 4.88303e-4 1.957133 4.88287e-4 1.957133 0.2143483 1.932278 0.008084475 1.940316 4.88303e-4 1.957133 0.2143483 1.932278 0.008084475 1.957133 0.2143483 1.920752 0.2143484 1.179276 0.28561 1.053018 0.2528129 1.179276 0.2528129 1.935713 0.8029695 1.924004 0.7990155 1.920101 0.7871531 1.945016 0.8029695 1.935713 0.8029695 1.920101 0.7871531 1.920101 0.570132 1.924004 0.5582697 1.935713 0.5543157 1.920101 0.570132 1.935713 0.5543157 1.945016 0.5543156 1.000488 0.3205851 1.044068 0.3329567 1.000488 0.3329567 1.272555 0.2856099 1.295579 0.252813 1.295579 0.2856099 1.193269 0.907238 1.205131 0.9111408 1.209085 0.9228498 1.166933 0.9072378 1.193269 0.907238 1.209085 0.9228498 1.000488 0.92285 1.004442 0.9111411 1.016304 0.907238 1.000488 0.92285 1.016304 0.907238 1.042641 0.9072379 1.728519 0.4506204 1.728519 0.4958242 1.718715 0.4958242 1.710524 0.4326251 1.728519 0.4506204 1.718715 0.4958242 1.710524 0.4326251 1.725179 0.4359653 1.728519 0.4506204 1.626433 0.4419283 1.718715 0.4958242 1.432625 0.6419227 1.272555 0.2528129 1.295579 0.2140727 1.295579 0.252813 1.718715 0.4958242 1.718715 0.6065858 1.432625 0.6419227 1.432625 0.6419227 1.475616 0.4419285 1.626433 0.4419283 1.718715 0.6065858 1.710385 0.6419227 1.432625 0.6419227 1.731102 0.7581059 1.858635 0.7581059 1.867367 0.7610166 1.867367 0.7610166 1.722371 0.7610161 1.731102 0.7581059 1.870142 0.5603047 1.742609 0.5603047 1.733877 0.5573942 1.733877 0.5573942 1.878873 0.5573942 1.870142 0.5603047 1.719089 0.9275556 1.719089 0.8400775 1.721999 0.831346 1.721999 0.831346 1.721999 0.9362868 1.719089 0.9275556 1.057524 0.2874242 1.145002 0.2874242 1.153734 0.2903351 1.153734 0.2903351 1.048793 0.2903351 1.057524 0.2874242 1.14918 0.07562226 1.141682 0.0840274 1.136054 0.05899429 1.142777 0.05496656 1.14598 0.04982274 1.152668 0.06678771 1.449634 0.9265977 1.454137 0.9357835 1.449634 0.9357835 1.565234 0.9357835 1.577549 0.9265977 1.577549 0.9357835 1.444498 0.9247831 1.456524 0.9155978 1.456524 0.9247831 1.379746 0.9265977 1.40003 0.9357835 1.379746 0.9357835 1.047357 0.01762789 1.051834 0.06548821 1.045888 0.07377058 1.152293 0.02071493 1.14598 0.04982274 1.145941 0.02213335 1.071551 0.05187094 1.06206 0.053842 1.06636 0.04771524 1.14918 0.07562226 1.152668 0.06678771 1.15839 0.07515925 1.15839 0.07515925 1.153132 0.08474558 1.14918 0.07562226 1.068279 0.006764054 1.103204 4.88464e-4 1.103101 0.006463944 1.141682 0.0840274 1.153132 0.08474558 1.129347 0.09187269 1.127641 0.1844576 1.101071 0.1931164 1.101071 0.1844576 1.129347 0.09187269 1.12823 0.0844019 1.141682 0.0840274 1.141682 0.0840274 1.14918 0.07562226 1.153132 0.08474558 1.15626 0.1758696 1.15626 0.1844575 1.127641 0.1844576 1.127641 0.1844576 1.149798 0.1758696 1.15626 0.1758696 1.064468 0.04335635 1.059615 0.0207507 1.064993 0.02227306 1.123577 0.06251293 1.102103 0.08445197 1.102368 0.06344956 1.068732 0.05807965 1.062461 0.08306509 1.05513 0.07444918 1.051834 0.06548821 1.058948 0.04857367 1.06206 0.053842 1.523443 0.9357835 1.527945 0.9265979 1.527945 0.9357835 1.505697 0.9155978 1.541137 0.9247834 1.505697 0.9247834 1.48879 0.9357835 1.523443 0.9265977 1.523443 0.9357835 1.07353 0.1931163 1.045883 0.2023016 1.045883 0.193116 1.389918 0.9247831 1.444498 0.9155978 1.444498 0.9247831 1.554871 0.9155978 1.566898 0.9247831 1.554871 0.9247831 1.053269 0.01916384 1.058948 0.04857367 1.051834 0.06548821 1.140609 0.0445531 1.145941 0.02213335 1.14598 0.04982274 1.05513 0.07444918 1.050949 0.0835188 1.045888 0.07377058 1.045888 0.07377058 1.051834 0.06548821 1.05513 0.07444918 1.062461 0.08306509 1.074652 0.0912249 1.050949 0.0835188 1.045883 0.1844576 1.07353 0.1931163 1.045883 0.193116 1.074652 0.0912249 1.062461 0.08306509 1.07595 0.08376377 1.062461 0.08306509 1.050949 0.0835188 1.05513 0.07444918 1.045883 0.1758695 1.052344 0.1758695 1.074501 0.1844576 1.074501 0.1844576 1.045883 0.1844576 1.045883 0.1758695 1.295579 0.205219 1.318602 0.2140727 1.295579 0.2140727 1.318602 0.3329197 1.295579 0.3452492 1.295579 0.3329195 1.884241 0.9410114 1.862386 0.952134 1.862386 0.9410116 1.920263 0.223552 1.957133 0.2327558 1.920101 0.2327558 1.318602 0.3205383 1.364925 0.2944475 1.364925 0.3205381 1.957133 0.3202335 1.920101 0.2327558 1.957133 0.2327558 1.157729 0.907238 1.166933 0.9326535 1.157729 0.9326534 1.044068 0.3329567 1.000488 0.3452001 1.000488 0.3329567 1.042641 0.9326536 1.000488 0.92285 1.042641 0.9072379 1.728519 0.6419227 1.718715 0.6065858 1.728519 0.6065858 1.053018 0.2528129 1.179276 0.2140728 1.179276 0.2528129 1.042641 0.9072379 1.051845 0.9326536 1.042641 0.9326536 1.000488 0.28561 1.044068 0.2944945 1.000488 0.2944943 1.364925 0.252813 1.373903 0.28561 1.364925 0.28561 1.373903 0.28561 1.460565 0.2528128 1.460565 0.2856102 1.469512 0.2528128 1.460565 0.2856102 1.460565 0.2528128 1.460565 0.2140728 1.469512 0.2528128 1.460565 0.2528128 1.044068 0.2051816 1.000488 0.2140725 1.000488 0.2051817 1.469512 0.2944943 1.505545 0.2856101 1.505545 0.2944943 1.156644 0.2990664 1.048793 0.2903351 1.153734 0.2903351 1.530928 0.9357835 1.553072 0.9265979 1.553072 0.9357835 1.558196 0.9357835 1.565234 0.9265977 1.565234 0.9357835 1.527945 0.9357835 1.530928 0.9265979 1.530928 0.9357835 1.057892 0.01086807 1.047357 0.01762789 1.053874 0.006297409 1.045883 0.09480309 1.055068 0.1021202 1.045883 0.1021202 1.07595 0.08376377 1.068732 0.05807965 1.081175 0.06195604 1.15626 0.2023016 1.128612 0.1931164 1.15626 0.1931163 1.412345 0.9265977 1.419383 0.9357835 1.412345 0.9357835 1.566897 0.9155978 1.621477 0.9247831 1.566898 0.9247831 1.40003 0.9265977 1.412345 0.9357835 1.40003 0.9357835 1.470259 0.9247834 1.505697 0.9155978 1.505697 0.9247834 1.295579 4.88289e-4 1.272555 0.2052192 1.272555 4.88297e-4 1.295579 0.3205384 1.318602 0.2944474 1.318602 0.3205383 1.295579 0.3452492 1.272555 0.3329195 1.295579 0.3329195 1.318602 0.3205383 1.295579 0.3329195 1.295579 0.3205384 1.295579 0.3329195 1.272555 0.3205384 1.295579 0.3205384 1.945016 0.5964685 1.920101 0.570132 1.945016 0.5543156 1.906096 0.9521344 1.884241 0.9410114 1.906096 0.9410116 1.791454 0.9521344 1.862386 0.9410116 1.862386 0.952134 1.469512 0.3452002 1.505545 0.3329566 1.505545 0.3452002 1.884065 0.2143492 1.918286 0.2235528 1.883715 0.2235527 1.883715 0.2235527 1.918287 0.2327569 1.883598 0.2327569 1.957133 0.3294374 1.920751 0.3386411 1.920264 0.3294375 1.957133 0.3202335 1.920264 0.3294375 1.920101 0.3202334 1.272555 0.3452491 1.188232 0.3329193 1.272555 0.3329195 1.920101 0.7516131 1.945016 0.7608169 1.920101 0.7608169 1.123011 0.05257523 1.08002 0.04160183 1.123011 0.04160183 1.945016 0.6148759 1.920101 0.6056721 1.945016 0.6056721 1.920752 0.2143484 1.957133 0.2235522 1.920263 0.223552 1.051844 0.9072378 1.061048 0.9326534 1.051845 0.9326536 1.148526 0.9326536 1.157729 0.907238 1.157729 0.9326534 1.044068 0.2944945 1.000488 0.3205851 1.000488 0.2944943 1.000488 0.2051817 1.044068 6.73867e-4 1.044068 0.2051816 1.364925 0.252813 1.373903 0.2140727 1.373903 0.2528129 1.944592 0.8284353 1.730731 0.9391972 1.730731 0.8284351 1.000488 0.2528129 1.044068 0.28561 1.000488 0.28561 1.945016 0.7516131 1.920101 0.7424094 1.945016 0.7424094 1.918286 0.36029 1.883598 0.2327569 1.918287 0.2327569 1.710524 0.4326251 1.626433 0.4419283 1.626433 0.4326247 1.469512 0.3205853 1.505545 0.3329566 1.469512 0.3329566 1.044068 0.2528129 1.053018 0.2140728 1.053018 0.2528129 1.179276 0.2140728 1.188231 0.252813 1.179276 0.2528129 1.295579 0.2944474 1.318602 0.2856103 1.318602 0.2944474 1.295579 0.2856099 1.318602 0.2528129 1.318602 0.2856103 1.364925 0.2944475 1.318602 0.2856103 1.364925 0.28561 1.318602 0.2856103 1.364925 0.252813 1.364925 0.28561 1.272555 0.2140727 1.188232 0.2052192 1.272555 0.2052192 1.295579 0.2140727 1.318602 0.2528129 1.295579 0.252813 1.188231 0.252813 1.272555 0.2140727 1.272555 0.2528129 1.318602 0.2052192 1.295579 4.88289e-4 1.318603 4.88513e-4 1.364925 0.2052192 1.318603 4.88513e-4 1.364925 4.88281e-4 1.469512 0.2140727 1.505545 0.2528129 1.469512 0.2528128 1.505545 0.2140728 1.469512 0.2051753 1.505545 0.2051752 1.505545 0.2051752 1.469512 5.12323e-4 1.505545 5.12315e-4 1.505545 0.2528129 1.469512 0.2856102 1.469512 0.2528128 1.881784 0.5486628 1.730967 0.3348015 1.881784 0.3348016 1.000488 0.2528129 1.044068 0.2140728 1.044068 0.2528129 1.730967 0.5486626 1.878873 0.5573942 1.733877 0.5573942 1.730731 0.9391972 1.721999 0.831346 1.730731 0.8284351 1.14343 0.01716881 1.137722 0.007961034 1.147923 0.01234704 1.152668 0.06678771 1.136054 0.05899429 1.142777 0.05496656 1.136949 0.01433765 1.103101 0.006463944 1.137722 0.007961034 1.152293 0.02071493 1.14343 0.01716881 1.147923 0.01234704 1.136054 0.05899429 1.12823 0.0844019 1.123577 0.06251293 1.424507 0.9265977 1.446652 0.9357835 1.424507 0.9357835 1.128612 0.2023019 1.101071 0.1931164 1.128612 0.1931164 1.101071 0.1931164 1.07353 0.2023016 1.07353 0.1931163 1.446652 0.9265977 1.449634 0.9357835 1.446652 0.9357835 1.541136 0.9155978 1.554871 0.9247831 1.541137 0.9247834 1.12823 0.0844019 1.102014 0.09187269 1.102103 0.08445197 1.102368 0.06344956 1.122161 0.05621325 1.123577 0.06251293 1.139571 0.02124476 1.136949 0.01433765 1.14343 0.01716881 1.067514 8.04474e-4 1.057892 0.01086807 1.053874 0.006297409 1.133425 0.0527479 1.142777 0.05496656 1.136054 0.05899429 1.13594 0.01979029 1.102993 0.01307231 1.136949 0.01433765 1.103204 4.88464e-4 1.137722 0.007961034 1.103101 0.006463944 1.145941 0.02213335 1.139571 0.02124476 1.14343 0.01716881 1.081175 0.06195604 1.071551 0.05187094 1.082787 0.05568909 1.15626 0.1844575 1.128612 0.1931164 1.127641 0.1844576 1.081175 0.06195604 1.102103 0.08445197 1.07595 0.08376377 1.138665 0.04879873 1.14598 0.04982274 1.142777 0.05496656 1.068847 0.01318633 1.103101 0.006463944 1.102993 0.01307231 1.454137 0.9265977 1.48879 0.9357835 1.454137 0.9357835 1.139076 0.1680715 1.12989 0.1608373 1.139076 0.1608373 1.149798 0.1758696 1.15626 0.1666837 1.15626 0.1758696 1.621477 0.9247831 1.631649 0.9155975 1.631649 0.9247834 1.07595 0.08376377 1.102014 0.09187269 1.074652 0.0912249 1.102368 0.06344956 1.082787 0.05568909 1.102452 0.05688887 1.059615 0.0207507 1.066018 0.02002781 1.064993 0.02227306 1.138676 0.00206077 1.147923 0.01234704 1.137722 0.007961034 1.06636 0.04771524 1.058948 0.04857367 1.064468 0.04335635 1.069677 0.01867198 1.102993 0.01307231 1.102902 0.01896369 1.074501 0.1844576 1.101071 0.1931164 1.07353 0.1931163 1.364925 0.3329192 1.318602 0.3452491 1.318602 0.3329197 1.918286 0.36029 1.883715 0.3694932 1.883598 0.36029 1.272555 0.2944474 1.295579 0.2856099 1.295579 0.2944474 1.906096 0.9410116 1.942511 0.9521344 1.906096 0.9521344 1.272555 0.2944474 1.188232 0.3205384 1.188232 0.2944475 1.318602 0.3329197 1.364925 0.3205381 1.364925 0.3329192 1.061048 0.9072378 1.148526 0.9326536 1.061048 0.9326534 1.920101 0.7871531 1.945016 0.7608169 1.945016 0.8029695 1.71946 0.8119004 1.870277 0.7697482 1.870277 0.8119004 1.209085 0.9228498 1.166933 0.9326535 1.166933 0.9072378 1.188231 0.252813 1.179276 0.28561 1.179276 0.2528129 1.053018 0.28561 1.044068 0.2528129 1.053018 0.2528129 1.188232 0.2944475 1.272555 0.2856099 1.272555 0.2944474 1.945016 0.6056721 1.920101 0.5964685 1.945016 0.5964685 1.364925 0.2052192 1.318602 0.2140727 1.318602 0.2052192 1.318602 0.2140727 1.364925 0.252813 1.318602 0.2528129 1.272555 0.2140727 1.295579 0.205219 1.295579 0.2140727 1.272555 4.88297e-4 1.188232 0.2052192 1.188232 4.88337e-4 1.272555 0.3329195 1.188232 0.3205384 1.272555 0.3205384 1.505545 0.2944943 1.469512 0.3205853 1.469512 0.2944943 1.71946 0.769748 1.867367 0.7610166 1.870277 0.7697482 1.062268 0.01583838 1.068279 0.006764054 1.068847 0.01318633 1.051834 0.06548821 1.068732 0.05807965 1.05513 0.07444918 1.053269 0.01916384 1.062268 0.01583838 1.059615 0.0207507 1.419383 0.9265977 1.424507 0.9357835 1.419383 0.9357835 1.553072 0.9357835 1.558196 0.9265977 1.558196 0.9357835 1.389918 0.9247831 1.379746 0.9155975 1.389918 0.9155975 1.147923 0.01234704 1.158206 0.01933556 1.152293 0.02071493 1.139076 0.1680715 1.12989 0.1753889 1.125262 0.1680715 1.577549 0.9357835 1.597833 0.9265977 1.597833 0.9357831 1.456524 0.9247831 1.470259 0.9155978 1.470259 0.9247834 1.055069 0.08756864 1.045883 0.09480309 1.045883 0.08756864 1.052344 0.1758695 1.045883 0.1666837 1.052344 0.1666837 1.066018 0.02002781 1.068847 0.01318633 1.069677 0.01867198 1.133425 0.0527479 1.123577 0.06251293 1.122161 0.05621325 1.272555 0.3205384 1.295579 0.2944474 1.295579 0.3205384 1.475616 0.4419285 1.432625 0.6419227 1.432625 0.4419285 1.158206 0.01933556 1.152668 0.06678771 1.152293 0.02071493 0.1602049 4.88286e-4 0.1656056 0.1149616 0.1656055 4.88286e-4 0.3668324 4.88286e-4 0.4252825 0.1296843 0.4379963 4.88286e-4 0.1602049 0.1149616 0.1656055 0.1191003 0.1656056 0.1149616 0.718721 0.1367283 0.8513208 0.18937 0.8513209 0.1367283 0.5584729 0.8715661 0.6886763 0.8886547 0.6886763 0.8715661 0.122774 0.03978753 0.06735414 0.02267414 0.07119172 0.03978765 0.7187211 4.88286e-4 0.8513209 0.1268674 0.8513208 4.88286e-4 0.9742742 0.475126 0.9995117 0.3395631 0.9742742 0.3395631 0.9742742 0.7152901 0.9995117 0.4839324 0.9742742 0.4839326 0.4301471 0.09963738 0.4476855 0.1131566 0.4476855 0.09963732 0.7033466 0.1367283 0.718721 0.1324492 0.7033466 0.1322978 0.9742742 0.4795293 0.9995117 0.4839324 0.9995117 0.4795292 0.1201953 0.6398431 0.1241632 0.6338987 0.1201952 0.6338989 0.9672788 0.8244635 0.9849687 0.8827466 0.9859736 0.8247719 0.9878022 0.1162673 0.9589475 0.1224743 0.9878022 0.1224736 0.4394726 0.4166052 0.46257 0.2874245 0.4269233 0.2874243 0.9589475 0.1286842 0.9878022 0.3377475 0.9878022 0.1286842 0.1656056 0.123239 0.160205 0.1693082 0.1656055 0.1693081 0.9589474 0.1162674 0.9878022 0.08591735 0.969421 0.08381986 0.9507004 0.7686162 0.9672788 0.7764334 0.9672788 0.7686162 0.9589475 0.1224743 0.9878022 0.1286842 0.9878022 0.1224736 0.1656055 0.1191003 0.1602049 0.123239 0.1656056 0.123239 0.2135179 0.7880615 4.88282e-4 0.7880615 0.2079482 0.9054236 0.7033466 4.88286e-4 0.718721 0.1268674 0.7187211 4.88286e-4 0.851321 0.2727802 0.718721 0.3340762 0.8513208 0.3212934 0.04630947 0.2041161 0.09486085 0.2091332 0.09455049 0.2041161 0.5634874 0.9075481 0.6936855 0.8904688 0.5634874 0.8904688 0.1370818 0.1372556 0.1542612 0.08812946 0.1370818 0.09151941 0.5634765 0.8697519 0.6936799 0.8526635 0.5634765 0.8526635 0.9507005 0.554348 0.9672788 0.7686162 0.9672788 0.5542747 0.1102058 0.9344678 0.07455897 0.9395559 0.1102058 0.9395559 0.158074 0.19422 0.1752538 0.1711225 0.158074 0.1711224 0.9698835 0.03194242 0.9878022 0.001010596 0.9589475 5.04342e-4 0.4497116 0.08430391 0.4321468 0.09782314 0.4497116 0.09782314 0.718721 0.1324492 0.7033464 0.1268675 0.7033466 0.1322978 0.3667389 0.1830862 0.4183209 0.1695669 0.3667389 0.1695669 0.1241632 0.6338987 0.1281312 0.6398431 0.1281311 0.6338989 0.9672788 0.7764334 0.9507007 0.7841923 0.9672788 0.7841923 0.8513209 0.1312991 0.718721 0.1268674 0.718721 0.1324492 5.41001e-4 0.9344677 0.0719918 0.939536 0.0722782 0.934468 0.9672788 0.8824383 0.9672788 0.8244635 0.9507004 0.9089362 0.558473 0.8697519 0.5634765 0.8526635 0.558473 0.8526635 0.6886763 0.8715661 0.6936799 0.8886547 0.6936799 0.8715661 0.3343058 0.6398431 0.1281311 0.6338989 0.1281312 0.6398431 0.718721 0.1367283 0.8513209 0.1312991 0.718721 0.1324492 0.7033466 0.3603313 0.7187211 0.2598316 0.718721 0.2077418 0.7033466 0.3603313 0.718721 0.3340762 0.7187211 0.2598316 0.7033466 0.3603313 0.718721 0.3603313 0.718721 0.3340762 0.9742742 0.475126 0.9995117 0.4795292 0.9995117 0.4751258 0.9698835 0.03194242 0.9589474 0.1162674 0.969421 0.08381986 0.7033466 0.1367283 0.718721 0.2077418 0.718721 0.1367283 0.5584729 0.9075482 0.5634874 0.8904688 0.5584731 0.8904688 4.88281e-4 0.6398431 0.1201952 0.6338989 4.88281e-4 0.6338987 1.160205 4.88286e-4 1.165606 0.1149616 1.160205 0.1149616 1.366832 4.88286e-4 1.425282 0.1296843 1.379546 0.1296846 1.165606 0.1191003 1.160205 0.1149616 1.165606 0.1149616 1.851321 0.18937 1.718721 0.1367283 1.851321 0.1367283 1.558473 0.8715661 1.688676 0.8886547 1.558473 0.8886547 1.122774 0.03978753 1.067354 0.02267414 1.12673 0.0226742 1.718721 4.88286e-4 1.851321 0.1268674 1.718721 0.1268674 1.999512 0.3395631 1.974274 0.475126 1.974274 0.3395631 1.999512 0.4839324 1.974274 0.7152901 1.974274 0.4839326 1.430147 0.09963738 1.447685 0.1131566 1.430147 0.117868 1.703347 0.1367283 1.718721 0.1324492 1.718721 0.1367283 1.999512 0.4839324 1.974274 0.4795293 1.999512 0.4795292 1.124163 0.6338987 1.120195 0.6398431 1.120195 0.6338989 1.984969 0.8827466 1.967279 0.8244635 1.985974 0.8247719 1.987802 0.1162673 1.958947 0.1224743 1.958947 0.1162674 1.439473 0.4166052 1.46257 0.2874245 1.46257 0.4166054 1.958947 0.1286842 1.987802 0.3377475 1.958947 0.3377504 1.165606 0.123239 1.160205 0.1693082 1.160205 0.123239 1.958947 0.1162674 1.987802 0.08591735 1.987802 0.1162673 1.967279 0.7764334 1.9507 0.7686162 1.967279 0.7686162 1.987802 0.1286842 1.958947 0.1224743 1.987802 0.1224736 1.165606 0.1191003 1.160205 0.123239 1.160205 0.1191003 1.213518 0.7880615 1.213518 0.8998538 1.207948 0.9054236 1.718721 0.1268674 1.703346 4.88286e-4 1.718721 4.88286e-4 1.851321 0.2727802 1.718721 0.3340762 1.718721 0.2598316 1.046309 0.2041161 1.094861 0.2091332 1.04595 0.2091332 1.693686 0.8904688 1.563487 0.9075481 1.563487 0.8904688 1.137082 0.1372556 1.154261 0.08812946 1.154261 0.1406455 1.69368 0.8526635 1.563477 0.8697519 1.563477 0.8526635 1.9507 0.554348 1.967279 0.7686162 1.9507 0.7686162 1.110206 0.9344678 1.074559 0.9395559 1.07421 0.9344678 1.158074 0.19422 1.175254 0.1711225 1.175254 0.1976141 1.969883 0.03194242 1.987802 0.001010596 1.987802 0.0278356 1.432147 0.09782314 1.449712 0.08430391 1.449712 0.09782314 1.703346 0.1268675 1.718721 0.1324492 1.703346 0.1322978 1.418321 0.1695669 1.366739 0.1830862 1.366739 0.1695669 1.124163 0.6338987 1.128131 0.6398431 1.124163 0.6398431 1.967279 0.7764334 1.950701 0.7841923 1.950701 0.7764334 1.718721 0.1268674 1.851321 0.1312991 1.718721 0.1324492 1.000541 0.9344677 1.071992 0.939536 1.000827 0.939536 1.967279 0.8244635 1.967279 0.8824383 1.9507 0.9089362 1.563477 0.8526635 1.558473 0.8697519 1.558473 0.8526635 1.688676 0.8715661 1.69368 0.8886547 1.688676 0.8886547 1.334306 0.6398431 1.128131 0.6338989 1.334306 0.6338987 1.718721 0.1367283 1.851321 0.1312991 1.851321 0.1367283 1.703346 0.3603313 1.718721 0.2077418 1.718721 0.2598316 1.703346 0.3603313 1.718721 0.2598316 1.718721 0.3340762 1.703346 0.3603313 1.718721 0.3340762 1.718721 0.3603313 1.999512 0.4795292 1.974274 0.475126 1.999512 0.4751258 1.969883 0.03194242 1.958947 0.1162674 1.958947 5.04342e-4 1.718721 0.2077418 1.703347 0.1367283 1.718721 0.1367283 1.563487 0.8904688 1.558473 0.9075482 1.558473 0.8904688 1.000488 0.6398431 1.120195 0.6338989 1.120195 0.6398431 1.160205 4.88286e-4 1.165606 0.1149616 1.160205 0.1149616 1.366832 4.88286e-4 1.425282 0.1296843 1.379546 0.1296846 1.165606 0.1191003 1.160205 0.1149616 1.165606 0.1149616 1.851321 0.18937 1.718721 0.1367283 1.851321 0.1367283 1.558473 0.8715661 1.688676 0.8886547 1.558473 0.8886547 1.122774 0.03978753 1.067354 0.02267414 1.12673 0.0226742 1.718721 4.88286e-4 1.851321 0.1268674 1.718721 0.1268674 1.999512 0.3395631 1.974274 0.475126 1.974274 0.3395631 1.999512 0.4839324 1.974274 0.7152901 1.974274 0.4839326 1.430147 0.09963738 1.447685 0.1131566 1.430147 0.117868 1.703347 0.1367283 1.718721 0.1324492 1.718721 0.1367283 1.999512 0.4839324 1.974274 0.4795293 1.999512 0.4795292 1.124163 0.6338987 1.120195 0.6398431 1.120195 0.6338989 1.984969 0.8827466 1.967279 0.8244635 1.985974 0.8247719 1.987802 0.1162673 1.958947 0.1224743 1.958947 0.1162674 1.439473 0.4166052 1.46257 0.2874245 1.46257 0.4166054 1.958947 0.1286842 1.987802 0.3377475 1.958947 0.3377504 1.165606 0.123239 1.160205 0.1693082 1.160205 0.123239 1.958947 0.1162674 1.987802 0.08591735 1.987802 0.1162673 1.967279 0.7764334 1.9507 0.7686162 1.967279 0.7686162 1.987802 0.1286842 1.958947 0.1224743 1.987802 0.1224736 1.165606 0.1191003 1.160205 0.123239 1.160205 0.1191003 1.213518 0.7880615 1.213518 0.8998538 1.207948 0.9054236 1.718721 0.1268674 1.703346 4.88286e-4 1.718721 4.88286e-4 1.851321 0.2727802 1.718721 0.3340762 1.718721 0.2598316 1.046309 0.2041161 1.094861 0.2091332 1.04595 0.2091332 1.693686 0.8904688 1.563487 0.9075481 1.563487 0.8904688 1.137082 0.1372556 1.154261 0.08812946 1.154261 0.1406455 1.69368 0.8526635 1.563477 0.8697519 1.563477 0.8526635 1.9507 0.554348 1.967279 0.7686162 1.9507 0.7686162 1.110206 0.9344678 1.074559 0.9395559 1.07421 0.9344678 1.158074 0.19422 1.175254 0.1711225 1.175254 0.1976141 1.969883 0.03194242 1.987802 0.001010596 1.987802 0.0278356 1.432147 0.09782314 1.449712 0.08430391 1.449712 0.09782314 1.703346 0.1268675 1.718721 0.1324492 1.703346 0.1322978 1.418321 0.1695669 1.366739 0.1830862 1.366739 0.1695669 1.124163 0.6338987 1.128131 0.6398431 1.124163 0.6398431 1.967279 0.7764334 1.950701 0.7841923 1.950701 0.7764334 1.718721 0.1268674 1.851321 0.1312991 1.718721 0.1324492 1.000541 0.9344677 1.071992 0.939536 1.000827 0.939536 1.967279 0.8244635 1.967279 0.8824383 1.9507 0.9089362 1.563477 0.8526635 1.558473 0.8697519 1.558473 0.8526635 1.688676 0.8715661 1.69368 0.8886547 1.688676 0.8886547 1.334306 0.6398431 1.128131 0.6338989 1.334306 0.6338987 1.718721 0.1367283 1.851321 0.1312991 1.851321 0.1367283 1.703346 0.3603313 1.718721 0.2077418 1.718721 0.2598316 1.703346 0.3603313 1.718721 0.2598316 1.718721 0.3340762 1.703346 0.3603313 1.718721 0.3340762 1.718721 0.3603313 1.999512 0.4795292 1.974274 0.475126 1.999512 0.4751258 1.969883 0.03194242 1.958947 0.1162674 1.958947 5.04342e-4 1.718721 0.2077418 1.703347 0.1367283 1.718721 0.1367283 1.563487 0.8904688 1.558473 0.9075482 1.558473 0.8904688 1.000488 0.6398431 1.120195 0.6338989 1.120195 0.6398431 1.160205 4.88286e-4 1.165606 0.1149616 1.165606 4.88286e-4 1.366832 4.88286e-4 1.425282 0.1296843 1.437996 4.88286e-4 1.160205 0.1149616 1.165606 0.1191003 1.165606 0.1149616 1.718721 0.1367283 1.851321 0.18937 1.851321 0.1367283 1.558473 0.8715661 1.688676 0.8886547 1.688676 0.8715661 1.122774 0.03978753 1.067354 0.02267414 1.071192 0.03978765 1.718721 4.88286e-4 1.851321 0.1268674 1.851321 4.88286e-4 1.974274 0.475126 1.999512 0.3395631 1.974274 0.3395631 1.974274 0.7152901 1.999512 0.4839324 1.974274 0.4839326 1.430147 0.09963738 1.447685 0.1131566 1.447686 0.09963732 1.703347 0.1367283 1.718721 0.1324492 1.703346 0.1322978 1.974274 0.4795293 1.999512 0.4839324 1.999512 0.4795292 1.120195 0.6398431 1.124163 0.6338987 1.120195 0.6338989 1.967279 0.8244635 1.984969 0.8827466 1.985974 0.8247719 1.987802 0.1162673 1.958947 0.1224743 1.987802 0.1224736 1.439473 0.4166052 1.46257 0.2874245 1.426923 0.2874243 1.958947 0.1286842 1.987802 0.3377475 1.987802 0.1286842 1.165606 0.123239 1.160205 0.1693082 1.165606 0.1693081 1.958947 0.1162674 1.987802 0.08591735 1.969421 0.08381986 1.9507 0.7686162 1.967279 0.7764334 1.967279 0.7686162 1.958947 0.1224743 1.987802 0.1286842 1.987802 0.1224736 1.165606 0.1191003 1.160205 0.123239 1.165606 0.123239 1.213518 0.7880615 1.000488 0.7880615 1.207948 0.9054236 1.703346 4.88286e-4 1.718721 0.1268674 1.718721 4.88286e-4 1.851321 0.2727802 1.718721 0.3340762 1.851321 0.3212934 1.046309 0.2041161 1.094861 0.2091332 1.09455 0.2041161 1.563487 0.9075481 1.693686 0.8904688 1.563487 0.8904688 1.137082 0.1372556 1.154261 0.08812946 1.137082 0.09151941 1.563477 0.8697519 1.69368 0.8526635 1.563477 0.8526635 1.9507 0.554348 1.967279 0.7686162 1.967279 0.5542747 1.110206 0.9344678 1.074559 0.9395559 1.110206 0.9395559 1.158074 0.19422 1.175254 0.1711225 1.158074 0.1711224 1.969883 0.03194242 1.987802 0.001010596 1.958947 5.04342e-4 1.449712 0.08430391 1.432147 0.09782314 1.449712 0.09782314 1.718721 0.1324492 1.703346 0.1268675 1.703346 0.1322978 1.366739 0.1830862 1.418321 0.1695669 1.366739 0.1695669 1.124163 0.6338987 1.128131 0.6398431 1.128131 0.6338989 1.967279 0.7764334 1.950701 0.7841923 1.967279 0.7841923 1.851321 0.1312991 1.718721 0.1268674 1.718721 0.1324492 1.000541 0.9344677 1.071992 0.939536 1.072278 0.934468 1.967279 0.8824383 1.967279 0.8244635 1.9507 0.9089362 1.558473 0.8697519 1.563477 0.8526635 1.558473 0.8526635 1.688676 0.8715661 1.69368 0.8886547 1.69368 0.8715661 1.334306 0.6398431 1.128131 0.6338989 1.128131 0.6398431 1.718721 0.1367283 1.851321 0.1312991 1.718721 0.1324492 1.703346 0.3603313 1.718721 0.2598316 1.718721 0.2077418 1.703346 0.3603313 1.718721 0.3340762 1.718721 0.2598316 1.703346 0.3603313 1.718721 0.3603313 1.718721 0.3340762 1.974274 0.475126 1.999512 0.4795292 1.999512 0.4751258 1.969883 0.03194242 1.958947 0.1162674 1.969421 0.08381986 1.703347 0.1367283 1.718721 0.2077418 1.718721 0.1367283 1.558473 0.9075482 1.563487 0.8904688 1.558473 0.8904688 1.000488 0.6398431 1.120195 0.6338989 1.000488 0.6338987 0.9182864 0.3694939 0.9182865 0.3786976 0.8840656 0.3786978 0.1566444 0.3412187 0.04588252 0.3412187 0.04588252 0.2990664 0.4605653 0.2528128 0.3739025 0.2528129 0.3739025 0.2140727 0.4280855 0.1316481 0.4280855 0.1205881 0.4634221 0.1205881 0.2725553 0.2528129 0.2725553 0.2856099 0.1882316 0.28561 0.9201011 0.7424094 0.9201011 0.6148759 0.9450164 0.6148759 0.4326246 0.4419285 0.4326246 0.4326248 0.4756163 0.4326248 0.1792764 0.28561 0.05301833 0.28561 0.05301839 0.2528129 4.88303e-4 0.3205851 0.04406827 0.3205851 0.04406833 0.3329567 0.2725553 0.2856099 0.2725553 0.2528129 0.2955789 0.252813 0.2725553 0.2528129 0.2725553 0.2140727 0.295579 0.2140727 0.4496341 0.9265977 0.4541368 0.9265977 0.4541367 0.9357835 0.5652344 0.9357835 0.5652345 0.9265977 0.5775492 0.9265977 0.4444977 0.9247831 0.4444976 0.9155978 0.456524 0.9155978 0.3797456 0.9265977 0.4000297 0.9265977 0.4000297 0.9357835 0.04735714 0.01762789 0.05326932 0.01916384 0.05183398 0.06548821 0.1522934 0.02071493 0.1526682 0.06678771 0.1459805 0.04982274 0.07155132 0.05187094 0.06873148 0.05807965 0.0620597 0.053842 0.06827884 0.006764054 0.06751406 8.04474e-4 0.1032041 4.88464e-4 0.1276409 0.1844576 0.1286125 0.1931164 0.1010712 0.1931164 0.06446784 0.04335635 0.05894839 0.04857367 0.05961465 0.0207507 0.123577 0.06251293 0.1282298 0.0844019 0.1021029 0.08445197 0.5234426 0.9357835 0.5234427 0.9265977 0.5279453 0.9265979 0.5056975 0.9155978 0.5411366 0.9155978 0.5411367 0.9247834 0.4887897 0.9357835 0.4887897 0.9265977 0.5234427 0.9265977 0.07352977 0.1931163 0.07352977 0.2023016 0.04588282 0.2023016 0.3899179 0.9247831 0.3899179 0.9155975 0.4444976 0.9155978 0.5548712 0.9155978 0.5668975 0.9155978 0.5668978 0.9247831 0.05326932 0.01916384 0.05961465 0.0207507 0.05894839 0.04857367 0.1406086 0.0445531 0.1405403 0.0235123 0.1459411 0.02213335 0.04588252 0.1844576 0.07450091 0.1844576 0.07352977 0.1931163 0.295579 0.205219 0.3186024 0.2052192 0.3186024 0.2140727 0.3186025 0.3329197 0.3186025 0.3452491 0.2955789 0.3452492 0.8842406 0.9410114 0.8842406 0.9521344 0.8623856 0.952134 0.9202634 0.223552 0.9571331 0.2235522 0.9571331 0.2327558 0.3186025 0.3205383 0.3186024 0.2944474 0.3649247 0.2944475 0.9571332 0.3202335 0.9201007 0.3202334 0.9201009 0.2327558 0.1577292 0.907238 0.166933 0.9072378 0.1669332 0.9326535 0.04406833 0.3329567 0.04406833 0.3452001 4.8831e-4 0.3452001 0.04264074 0.9326536 4.8834e-4 0.9326536 4.88282e-4 0.92285 0.728519 0.6419227 0.7103851 0.6419227 0.7187154 0.6065858 0.05301839 0.2528129 0.05301839 0.2140728 0.1792763 0.2140728 0.04264056 0.9072379 0.05184429 0.9072378 0.05184453 0.9326536 4.88281e-4 0.28561 0.04406827 0.28561 0.04406827 0.2944945 0.3649246 0.252813 0.3739025 0.2528129 0.3739026 0.28561 0.3739026 0.28561 0.3739025 0.2528129 0.4605653 0.2528128 0.4695122 0.2528128 0.4695124 0.2856102 0.4605652 0.2856102 0.4605651 0.2140728 0.4695124 0.2140727 0.4695122 0.2528128 0.04406833 0.2051816 0.04406833 0.2140728 4.88345e-4 0.2140725 0.4695124 0.2944943 0.4695124 0.2856102 0.5055451 0.2856101 0.04588252 0.2990664 0.04879301 0.2903351 0.153734 0.2903351 0.5309278 0.9357835 0.5309278 0.9265979 0.5530718 0.9265979 0.558196 0.9357835 0.558196 0.9265977 0.5652345 0.9265977 0.5279453 0.9357835 0.5279453 0.9265979 0.5309278 0.9265979 0.05789202 0.01086807 0.05326932 0.01916384 0.04735714 0.01762789 0.0458827 0.09480309 0.05969667 0.09480309 0.05506843 0.1021202 0.07595032 0.08376377 0.06246048 0.08306509 0.06873148 0.05807965 0.1562597 0.2023016 0.1286125 0.2023019 0.1286125 0.1931164 0.4123449 0.9265977 0.4193832 0.9265977 0.4193831 0.9357835 0.5668975 0.9155978 0.621477 0.9155975 0.6214771 0.9247831 0.4000297 0.9265977 0.4123449 0.9265977 0.4123449 0.9357835 0.4702587 0.9247834 0.4702587 0.9155978 0.5056975 0.9155978 0.2955788 4.88289e-4 0.295579 0.205219 0.2725553 0.2052192 0.2955789 0.3205384 0.295579 0.2944474 0.3186024 0.2944474 0.2955789 0.3452492 0.2725553 0.3452491 0.2725553 0.3329195 0.3186025 0.3205383 0.3186025 0.3329197 0.295579 0.3329195 0.295579 0.3329195 0.2725553 0.3329195 0.2725553 0.3205384 0.9450165 0.5964685 0.9201009 0.5964685 0.9201009 0.570132 0.9060957 0.9521344 0.8842406 0.9521344 0.8842406 0.9410114 0.7914544 0.9521344 0.7914544 0.9410114 0.8623856 0.9410116 0.4695124 0.3452002 0.4695124 0.3329566 0.5055454 0.3329566 0.8840655 0.2143492 0.9182865 0.2143492 0.9182864 0.2235528 0.883715 0.2235527 0.9182864 0.2235528 0.9182868 0.2327569 0.9571332 0.3294374 0.9571333 0.3386409 0.9207512 0.3386411 0.9571332 0.3202335 0.9571332 0.3294374 0.9202635 0.3294375 0.2725553 0.3452491 0.1882315 0.3452492 0.1882315 0.3329193 0.9201009 0.7516131 0.9450165 0.7516131 0.9450165 0.7608169 0.1230109 0.05257523 0.08001965 0.05257523 0.08001965 0.04160183 0.9450164 0.6148759 0.9201011 0.6148759 0.9201011 0.6056721 0.9207516 0.2143484 0.9571332 0.2143483 0.9571331 0.2235522 0.05184429 0.9072378 0.06104779 0.9072378 0.06104815 0.9326534 0.1485259 0.9326536 0.1485257 0.9072379 0.1577292 0.907238 0.04406827 0.2944945 0.04406827 0.3205851 4.88303e-4 0.3205851 4.88343e-4 0.2051817 4.88347e-4 6.73875e-4 0.04406833 6.73867e-4 0.3649246 0.252813 0.3649247 0.2140727 0.3739025 0.2140727 0.944592 0.8284353 0.9445921 0.9391971 0.730731 0.9391972 4.88342e-4 0.2528129 0.04406833 0.2528129 0.04406827 0.28561 0.9450165 0.7516131 0.9201009 0.7516131 0.9201011 0.7424094 0.9182865 0.36029 0.883598 0.36029 0.8835983 0.2327569 0.7105237 0.4326251 0.7187155 0.4958242 0.6264333 0.4419283 0.4695122 0.3205853 0.5055454 0.3205853 0.5055454 0.3329566 0.04406833 0.2528129 0.04406833 0.2140728 0.05301839 0.2140728 0.1792763 0.2140728 0.1882315 0.2140728 0.1882315 0.252813 0.295579 0.2944474 0.295579 0.2856099 0.3186024 0.2856103 0.295579 0.2856099 0.2955789 0.252813 0.3186024 0.2528129 0.3649247 0.2944475 0.3186024 0.2944474 0.3186024 0.2856103 0.3186024 0.2856103 0.3186024 0.2528129 0.3649246 0.252813 0.2725553 0.2140727 0.1882315 0.2140728 0.1882316 0.2052192 0.295579 0.2140727 0.3186024 0.2140727 0.3186024 0.2528129 0.1882315 0.252813 0.1882315 0.2140728 0.2725553 0.2140727 0.3186024 0.2052192 0.295579 0.205219 0.2955788 4.88289e-4 0.3649247 0.2052192 0.3186024 0.2052192 0.3186025 4.88513e-4 0.4695124 0.2140727 0.5055453 0.2140728 0.5055453 0.2528129 0.5055453 0.2140728 0.4695124 0.2140727 0.4695124 0.2051753 0.5055453 0.2051752 0.4695124 0.2051753 0.4695123 5.12323e-4 0.5055453 0.2528129 0.5055451 0.2856101 0.4695124 0.2856102 0.8817839 0.5486628 0.7309666 0.5486626 0.7309666 0.3348015 4.88342e-4 0.2528129 4.88345e-4 0.2140725 0.04406833 0.2140728 0.7309666 0.5486626 0.8817839 0.5486628 0.8788734 0.5573942 0.730731 0.9391972 0.7219995 0.9362868 0.7219994 0.831346 0.1434301 0.01716881 0.1369493 0.01433765 0.1377221 0.007961034 0.1526682 0.06678771 0.1491801 0.07562226 0.1360535 0.05899429 0.1369493 0.01433765 0.1029926 0.01307231 0.1031009 0.006463944 0.1522934 0.02071493 0.1459411 0.02213335 0.1434301 0.01716881 0.1360535 0.05899429 0.1416816 0.0840274 0.1282298 0.0844019 0.4245075 0.9265977 0.4466516 0.9265977 0.4466516 0.9357835 0.1286125 0.2023019 0.1010711 0.2023019 0.1010712 0.1931164 0.1010712 0.1931164 0.1010711 0.2023019 0.07352977 0.2023016 0.4466516 0.9265977 0.4496341 0.9265977 0.449634 0.9357835 0.5411366 0.9155978 0.5548712 0.9155978 0.5548712 0.9247831 0.1282298 0.0844019 0.1293473 0.09187269 0.1020137 0.09187269 0.1023678 0.06344956 0.1024522 0.05688887 0.1221608 0.05621325 0.139571 0.02124476 0.1359398 0.01979029 0.1369493 0.01433765 0.06751406 8.04474e-4 0.06827884 0.006764054 0.05789202 0.01086807 0.1334255 0.0527479 0.1386654 0.04879873 0.1427766 0.05496656 0.1359398 0.01979029 0.1029018 0.01896369 0.1029926 0.01307231 0.1032041 4.88464e-4 0.1386755 0.00206077 0.1377221 0.007961034 0.1459411 0.02213335 0.1405403 0.0235123 0.139571 0.02124476 0.08117532 0.06195604 0.06873148 0.05807965 0.07155132 0.05187094 0.1562597 0.1844575 0.1562598 0.1931163 0.1286125 0.1931164 0.08117532 0.06195604 0.1023678 0.06344956 0.1021029 0.08445197 0.1386654 0.04879873 0.1406086 0.0445531 0.1459805 0.04982274 0.06884676 0.01318633 0.06827884 0.006764054 0.1031009 0.006463944 0.4541368 0.9265977 0.4887897 0.9265977 0.4887897 0.9357835 0.1390759 0.1680715 0.1252617 0.1680715 0.1298903 0.1608373 0.149798 0.1758696 0.149798 0.1666839 0.1562597 0.1666837 0.6214771 0.9247831 0.621477 0.9155975 0.6316491 0.9155975 0.07595032 0.08376377 0.1021029 0.08445197 0.1020137 0.09187269 0.1023678 0.06344956 0.08117532 0.06195604 0.08278739 0.05568909 0.05961465 0.0207507 0.0622676 0.01583838 0.0660178 0.02002781 0.1386755 0.00206077 0.1520432 0.007921338 0.1479231 0.01234704 0.06636029 0.04771524 0.0620597 0.053842 0.05894839 0.04857367 0.06967717 0.01867198 0.06884676 0.01318633 0.1029926 0.01307231 0.07450091 0.1844576 0.1010711 0.1844576 0.1010712 0.1931164 0.3649246 0.3329192 0.3649246 0.3452492 0.3186025 0.3452491 0.9182865 0.36029 0.9182864 0.3694939 0.883715 0.3694932 0.2725553 0.2944474 0.2725553 0.2856099 0.295579 0.2856099 0.9060957 0.9410116 0.9425108 0.9410114 0.9425108 0.9521344 0.2725553 0.2944474 0.2725553 0.3205384 0.1882315 0.3205384 0.3186025 0.3329197 0.3186025 0.3205383 0.3649247 0.3205381 0.06104779 0.9072378 0.1485257 0.9072379 0.1485259 0.9326536 0.9201009 0.7871531 0.9201009 0.7608169 0.9450165 0.7608169 0.7194603 0.8119004 0.7194604 0.769748 0.8702774 0.7697482 0.2090855 0.9228498 0.2090857 0.9326535 0.1669332 0.9326535 0.1882315 0.252813 0.1882316 0.28561 0.1792764 0.28561 0.05301833 0.28561 0.04406827 0.28561 0.04406833 0.2528129 0.1882315 0.2944475 0.1882316 0.28561 0.2725553 0.2856099 0.9450164 0.6056721 0.9201011 0.6056721 0.9201009 0.5964685 0.3649247 0.2052192 0.3649247 0.2140727 0.3186024 0.2140727 0.3186024 0.2140727 0.3649247 0.2140727 0.3649246 0.252813 0.2725553 0.2140727 0.2725553 0.2052192 0.295579 0.205219 0.2725554 4.88297e-4 0.2725553 0.2052192 0.1882316 0.2052192 0.2725553 0.3329195 0.1882315 0.3329193 0.1882315 0.3205384 0.5055453 0.2944943 0.5055454 0.3205853 0.4695122 0.3205853 0.7194604 0.769748 0.7223711 0.7610161 0.867367 0.7610166 0.0622676 0.01583838 0.05789202 0.01086807 0.06827884 0.006764054 0.05183398 0.06548821 0.0620597 0.053842 0.06873148 0.05807965 0.05326932 0.01916384 0.05789202 0.01086807 0.0622676 0.01583838 0.4193832 0.9265977 0.4245075 0.9265977 0.4245074 0.9357835 0.5530717 0.9357835 0.5530718 0.9265979 0.558196 0.9265977 0.3899179 0.9247831 0.3797456 0.9247834 0.3797456 0.9155975 0.1479231 0.01234704 0.1520432 0.007921338 0.1582064 0.01933556 0.1390759 0.1680715 0.1390759 0.1753889 0.1298903 0.1753889 0.5775492 0.9357835 0.5775492 0.9265977 0.5978327 0.9265977 0.456524 0.9247831 0.456524 0.9155978 0.4702587 0.9155978 0.05506855 0.08756864 0.05969667 0.09480309 0.0458827 0.09480309 0.0523439 0.1758695 0.04588252 0.1758695 0.04588282 0.1666837 0.0660178 0.02002781 0.0622676 0.01583838 0.06884676 0.01318633 0.1334255 0.0527479 0.1360535 0.05899429 0.123577 0.06251293 0.2725553 0.3205384 0.2725553 0.2944474 0.295579 0.2944474 0.1582064 0.01933556 0.1583899 0.07515925 0.1526682 0.06678771 1.918286 0.3694939 1.883715 0.3694932 1.884066 0.3786978 1.045883 0.2990664 1.045883 0.3412187 1.156644 0.3412187 1.460565 0.2528128 1.460565 0.2140728 1.373903 0.2140727 1.463422 0.1205881 1.428085 0.1205881 1.428085 0.1316481 1.272555 0.2528129 1.188231 0.252813 1.188232 0.28561 1.945016 0.6148759 1.920101 0.6148759 1.920101 0.7424094 1.475616 0.4326248 1.432625 0.4326248 1.432625 0.4419285 1.179276 0.28561 1.179276 0.2528129 1.053018 0.2528129 1.044068 0.3329567 1.044068 0.3205851 1.000488 0.3205851 1.295579 0.252813 1.272555 0.2528129 1.272555 0.2856099 1.272555 0.2528129 1.295579 0.252813 1.295579 0.2140727 1.454137 0.9357835 1.454137 0.9265977 1.449634 0.9265977 1.577549 0.9265977 1.565234 0.9265977 1.565234 0.9357835 1.456524 0.9155978 1.444498 0.9155978 1.444498 0.9247831 1.40003 0.9357835 1.40003 0.9265977 1.379746 0.9265977 1.047357 0.01762789 1.045888 0.07377058 1.051834 0.06548821 1.152293 0.02071493 1.145941 0.02213335 1.14598 0.04982274 1.071551 0.05187094 1.06636 0.04771524 1.06206 0.053842 1.103204 4.88464e-4 1.067514 8.04474e-4 1.068279 0.006764054 1.127641 0.1844576 1.101071 0.1844576 1.101071 0.1931164 1.064468 0.04335635 1.064993 0.02227306 1.059615 0.0207507 1.123577 0.06251293 1.102368 0.06344956 1.102103 0.08445197 1.527945 0.9265979 1.523443 0.9265977 1.523443 0.9357835 1.541137 0.9247834 1.541136 0.9155978 1.505697 0.9155978 1.523443 0.9265977 1.48879 0.9265977 1.48879 0.9357835 1.045883 0.2023016 1.07353 0.2023016 1.07353 0.1931163 1.444498 0.9155978 1.389918 0.9155975 1.389918 0.9247831 1.566898 0.9247831 1.566897 0.9155978 1.554871 0.9155978 1.053269 0.01916384 1.051834 0.06548821 1.058948 0.04857367 1.140609 0.0445531 1.14598 0.04982274 1.145941 0.02213335 1.045883 0.1844576 1.045883 0.193116 1.07353 0.1931163 1.295579 0.205219 1.295579 0.2140727 1.318602 0.2140727 1.318602 0.3329197 1.295579 0.3329195 1.295579 0.3452492 1.884241 0.9410114 1.862386 0.9410116 1.862386 0.952134 1.920263 0.223552 1.920101 0.2327558 1.957133 0.2327558 1.364925 0.2944475 1.318602 0.2944474 1.318602 0.3205383 1.920101 0.2327558 1.920101 0.3202334 1.957133 0.3202335 1.157729 0.907238 1.157729 0.9326534 1.166933 0.9326535 1.000488 0.3452001 1.044068 0.3452001 1.044068 0.3329567 1.042641 0.9326536 1.042641 0.9072379 1.000488 0.92285 1.728519 0.6419227 1.728519 0.6065858 1.718715 0.6065858 1.053018 0.2528129 1.179276 0.2528129 1.179276 0.2140728 1.051845 0.9326536 1.051844 0.9072378 1.042641 0.9072379 1.000488 0.28561 1.000488 0.2944943 1.044068 0.2944945 1.373903 0.28561 1.373903 0.2528129 1.364925 0.252813 1.373903 0.28561 1.460565 0.2856102 1.460565 0.2528128 1.469512 0.2528128 1.460565 0.2528128 1.460565 0.2856102 1.460565 0.2140728 1.460565 0.2528128 1.469512 0.2528128 1.000488 0.2140725 1.044068 0.2140728 1.044068 0.2051816 1.505545 0.2856101 1.469512 0.2856102 1.469512 0.2944943 1.156644 0.2990664 1.153734 0.2903351 1.048793 0.2903351 1.553072 0.9265979 1.530928 0.9265979 1.530928 0.9357835 1.565234 0.9265977 1.558196 0.9265977 1.558196 0.9357835 1.530928 0.9265979 1.527945 0.9265979 1.527945 0.9357835 1.057892 0.01086807 1.053874 0.006297409 1.047357 0.01762789 1.045883 0.09480309 1.045883 0.1021202 1.055068 0.1021202 1.068732 0.05807965 1.062461 0.08306509 1.07595 0.08376377 1.128612 0.1931164 1.128612 0.2023019 1.15626 0.2023016 1.419383 0.9357835 1.419383 0.9265977 1.412345 0.9265977 1.621477 0.9247831 1.621477 0.9155975 1.566897 0.9155978 1.412345 0.9357835 1.412345 0.9265977 1.40003 0.9265977 1.505697 0.9155978 1.470259 0.9155978 1.470259 0.9247834 1.295579 4.88289e-4 1.272555 4.88297e-4 1.272555 0.2052192 1.318602 0.2944474 1.295579 0.2944474 1.295579 0.3205384 1.272555 0.3329195 1.272555 0.3452491 1.295579 0.3452492 1.318602 0.3205383 1.295579 0.3205384 1.295579 0.3329195 1.272555 0.3205384 1.272555 0.3329195 1.295579 0.3329195 1.945016 0.5964685 1.945016 0.5543156 1.920101 0.570132 1.906096 0.9521344 1.906096 0.9410116 1.884241 0.9410114 1.791454 0.9521344 1.862386 0.952134 1.862386 0.9410116 1.469512 0.3452002 1.505545 0.3452002 1.505545 0.3329566 1.884065 0.2143492 1.883715 0.2235527 1.918286 0.2235528 1.883715 0.2235527 1.883598 0.2327569 1.918287 0.2327569 1.957133 0.3294374 1.920264 0.3294375 1.920751 0.3386411 1.957133 0.3202335 1.920101 0.3202334 1.920264 0.3294375 1.272555 0.3452491 1.272555 0.3329195 1.188232 0.3329193 1.945016 0.7608169 1.945016 0.7516131 1.920101 0.7516131 1.08002 0.04160183 1.08002 0.05257523 1.123011 0.05257523 1.945016 0.6148759 1.945016 0.6056721 1.920101 0.6056721 1.920752 0.2143484 1.920263 0.223552 1.957133 0.2235522 1.061048 0.9326534 1.061048 0.9072378 1.051844 0.9072378 1.148526 0.9326536 1.157729 0.9326534 1.157729 0.907238 1.000488 0.3205851 1.044068 0.3205851 1.044068 0.2944945 1.044068 6.73867e-4 1.000488 6.73875e-4 1.000488 0.2051817 1.364925 0.252813 1.373903 0.2528129 1.373903 0.2140727 1.730731 0.9391972 1.944592 0.9391971 1.944592 0.8284353 1.000488 0.2528129 1.000488 0.28561 1.044068 0.28561 1.945016 0.7516131 1.945016 0.7424094 1.920101 0.7424094 1.883598 0.2327569 1.883598 0.36029 1.918286 0.36029 1.710524 0.4326251 1.626433 0.4326247 1.626433 0.4419283 1.505545 0.3329566 1.505545 0.3205853 1.469512 0.3205853 1.044068 0.2528129 1.053018 0.2528129 1.053018 0.2140728 1.179276 0.2140728 1.179276 0.2528129 1.188231 0.252813 1.318602 0.2856103 1.295579 0.2856099 1.295579 0.2944474 1.318602 0.2528129 1.295579 0.252813 1.295579 0.2856099 1.364925 0.2944475 1.364925 0.28561 1.318602 0.2856103 1.364925 0.252813 1.318602 0.2528129 1.318602 0.2856103 1.272555 0.2140727 1.272555 0.2052192 1.188232 0.2052192 1.295579 0.2140727 1.295579 0.252813 1.318602 0.2528129 1.272555 0.2140727 1.188232 0.2140728 1.188231 0.252813 1.318602 0.2052192 1.318603 4.88513e-4 1.295579 4.88289e-4 1.364925 0.2052192 1.364925 4.88281e-4 1.318603 4.88513e-4 1.505545 0.2528129 1.505545 0.2140728 1.469512 0.2140727 1.505545 0.2140728 1.505545 0.2051752 1.469512 0.2051753 1.469512 5.12323e-4 1.469512 0.2051753 1.505545 0.2051752 1.505545 0.2528129 1.469512 0.2528128 1.469512 0.2856102 1.730967 0.3348015 1.730967 0.5486626 1.881784 0.5486628 1.000488 0.2528129 1.044068 0.2528129 1.044068 0.2140728 1.730967 0.5486626 1.733877 0.5573942 1.878873 0.5573942 1.721999 0.831346 1.721999 0.9362868 1.730731 0.9391972 1.14343 0.01716881 1.147923 0.01234704 1.137722 0.007961034 1.152668 0.06678771 1.142777 0.05496656 1.136054 0.05899429 1.136949 0.01433765 1.137722 0.007961034 1.103101 0.006463944 1.152293 0.02071493 1.147923 0.01234704 1.14343 0.01716881 1.12823 0.0844019 1.141682 0.0840274 1.136054 0.05899429 1.446652 0.9357835 1.446652 0.9265977 1.424507 0.9265977 1.101071 0.1931164 1.101071 0.2023019 1.128612 0.2023019 1.07353 0.2023016 1.101071 0.2023019 1.101071 0.1931164 1.449634 0.9357835 1.449634 0.9265977 1.446652 0.9265977 1.554871 0.9247831 1.554871 0.9155978 1.541136 0.9155978 1.12823 0.0844019 1.102103 0.08445197 1.102014 0.09187269 1.102368 0.06344956 1.123577 0.06251293 1.122161 0.05621325 1.139571 0.02124476 1.14343 0.01716881 1.136949 0.01433765 1.067514 8.04474e-4 1.053874 0.006297409 1.057892 0.01086807 1.133425 0.0527479 1.136054 0.05899429 1.142777 0.05496656 1.13594 0.01979029 1.136949 0.01433765 1.102993 0.01307231 1.137722 0.007961034 1.138676 0.00206077 1.103204 4.88464e-4 1.145941 0.02213335 1.14343 0.01716881 1.139571 0.02124476 1.071551 0.05187094 1.068732 0.05807965 1.081175 0.06195604 1.15626 0.1844575 1.127641 0.1844576 1.128612 0.1931164 1.081175 0.06195604 1.07595 0.08376377 1.102103 0.08445197 1.138665 0.04879873 1.142777 0.05496656 1.14598 0.04982274 1.068847 0.01318633 1.102993 0.01307231 1.103101 0.006463944 1.48879 0.9357835 1.48879 0.9265977 1.454137 0.9265977 1.12989 0.1608373 1.125262 0.1680715 1.139076 0.1680715 1.149798 0.1758696 1.15626 0.1758696 1.15626 0.1666837 1.621477 0.9247831 1.631649 0.9247834 1.631649 0.9155975 1.07595 0.08376377 1.074652 0.0912249 1.102014 0.09187269 1.102368 0.06344956 1.102452 0.05688887 1.082787 0.05568909 1.059615 0.0207507 1.064993 0.02227306 1.066018 0.02002781 1.138676 0.00206077 1.137722 0.007961034 1.147923 0.01234704 1.06636 0.04771524 1.064468 0.04335635 1.058948 0.04857367 1.069677 0.01867198 1.102902 0.01896369 1.102993 0.01307231 1.074501 0.1844576 1.07353 0.1931163 1.101071 0.1931164 1.364925 0.3329192 1.318602 0.3329197 1.318602 0.3452491 1.918286 0.36029 1.883598 0.36029 1.883715 0.3694932 1.295579 0.2856099 1.272555 0.2856099 1.272555 0.2944474 1.906096 0.9410116 1.906096 0.9521344 1.942511 0.9521344 1.188232 0.3205384 1.272555 0.3205384 1.272555 0.2944474 1.318602 0.3329197 1.364925 0.3329192 1.364925 0.3205381 1.061048 0.9072378 1.061048 0.9326534 1.148526 0.9326536 1.920101 0.7871531 1.945016 0.8029695 1.945016 0.7608169 1.870277 0.7697482 1.71946 0.769748 1.71946 0.8119004 1.209085 0.9228498 1.166933 0.9072378 1.166933 0.9326535 1.188231 0.252813 1.179276 0.2528129 1.179276 0.28561 1.053018 0.28561 1.053018 0.2528129 1.044068 0.2528129 1.272555 0.2856099 1.188232 0.28561 1.188232 0.2944475 1.945016 0.6056721 1.945016 0.5964685 1.920101 0.5964685 1.364925 0.2052192 1.318602 0.2052192 1.318602 0.2140727 1.318602 0.2140727 1.318602 0.2528129 1.364925 0.252813 1.272555 0.2140727 1.295579 0.2140727 1.295579 0.205219 1.272555 4.88297e-4 1.188232 4.88337e-4 1.188232 0.2052192 1.272555 0.3329195 1.272555 0.3205384 1.188232 0.3205384 1.469512 0.3205853 1.505545 0.3205853 1.505545 0.2944943 1.867367 0.7610166 1.722371 0.7610161 1.71946 0.769748 1.062268 0.01583838 1.068847 0.01318633 1.068279 0.006764054 1.068732 0.05807965 1.06206 0.053842 1.051834 0.06548821 1.053269 0.01916384 1.059615 0.0207507 1.062268 0.01583838 1.424507 0.9357835 1.424507 0.9265977 1.419383 0.9265977 1.558196 0.9265977 1.553072 0.9265979 1.553072 0.9357835 1.389918 0.9247831 1.389918 0.9155975 1.379746 0.9155975 1.147923 0.01234704 1.152293 0.02071493 1.158206 0.01933556 1.139076 0.1680715 1.125262 0.1680715 1.12989 0.1753889 1.597833 0.9265977 1.577549 0.9265977 1.577549 0.9357835 1.470259 0.9155978 1.456524 0.9155978 1.456524 0.9247831 1.045883 0.09480309 1.059697 0.09480309 1.055069 0.08756864 1.052344 0.1758695 1.052344 0.1666837 1.045883 0.1666837 1.066018 0.02002781 1.069677 0.01867198 1.068847 0.01318633 1.123577 0.06251293 1.136054 0.05899429 1.133425 0.0527479 1.295579 0.2944474 1.272555 0.2944474 1.272555 0.3205384 1.158206 0.01933556 1.152293 0.02071493 1.152668 0.06678771 1.918286 0.3694939 1.883715 0.3694932 1.884066 0.3786978 1.045883 0.2990664 1.045883 0.3412187 1.156644 0.3412187 1.460565 0.2528128 1.460565 0.2140728 1.373903 0.2140727 1.463422 0.1205881 1.428085 0.1205881 1.428085 0.1316481 1.272555 0.2528129 1.188231 0.252813 1.188232 0.28561 1.945016 0.6148759 1.920101 0.6148759 1.920101 0.7424094 1.475616 0.4326248 1.432625 0.4326248 1.432625 0.4419285 1.179276 0.28561 1.179276 0.2528129 1.053018 0.2528129 1.044068 0.3329567 1.044068 0.3205851 1.000488 0.3205851 1.295579 0.252813 1.272555 0.2528129 1.272555 0.2856099 1.272555 0.2528129 1.295579 0.252813 1.295579 0.2140727 1.454137 0.9357835 1.454137 0.9265977 1.449634 0.9265977 1.577549 0.9265977 1.565234 0.9265977 1.565234 0.9357835 1.456524 0.9155978 1.444498 0.9155978 1.444498 0.9247831 1.40003 0.9357835 1.40003 0.9265977 1.379746 0.9265977 1.047357 0.01762789 1.045888 0.07377058 1.051834 0.06548821 1.152293 0.02071493 1.145941 0.02213335 1.14598 0.04982274 1.071551 0.05187094 1.06636 0.04771524 1.06206 0.053842 1.103204 4.88464e-4 1.067514 8.04474e-4 1.068279 0.006764054 1.127641 0.1844576 1.101071 0.1844576 1.101071 0.1931164 1.064468 0.04335635 1.064993 0.02227306 1.059615 0.0207507 1.123577 0.06251293 1.102368 0.06344956 1.102103 0.08445197 1.527945 0.9265979 1.523443 0.9265977 1.523443 0.9357835 1.541137 0.9247834 1.541136 0.9155978 1.505697 0.9155978 1.523443 0.9265977 1.48879 0.9265977 1.48879 0.9357835 1.045883 0.2023016 1.07353 0.2023016 1.07353 0.1931163 1.444498 0.9155978 1.389918 0.9155975 1.389918 0.9247831 1.566898 0.9247831 1.566897 0.9155978 1.554871 0.9155978 1.053269 0.01916384 1.051834 0.06548821 1.058948 0.04857367 1.140609 0.0445531 1.14598 0.04982274 1.145941 0.02213335 1.045883 0.1844576 1.045883 0.193116 1.07353 0.1931163 1.295579 0.205219 1.295579 0.2140727 1.318602 0.2140727 1.318602 0.3329197 1.295579 0.3329195 1.295579 0.3452492 1.884241 0.9410114 1.862386 0.9410116 1.862386 0.952134 1.920263 0.223552 1.920101 0.2327558 1.957133 0.2327558 1.364925 0.2944475 1.318602 0.2944474 1.318602 0.3205383 1.920101 0.2327558 1.920101 0.3202334 1.957133 0.3202335 1.157729 0.907238 1.157729 0.9326534 1.166933 0.9326535 1.000488 0.3452001 1.044068 0.3452001 1.044068 0.3329567 1.042641 0.9326536 1.042641 0.9072379 1.000488 0.92285 1.728519 0.6419227 1.728519 0.6065858 1.718715 0.6065858 1.053018 0.2528129 1.179276 0.2528129 1.179276 0.2140728 1.051845 0.9326536 1.051844 0.9072378 1.042641 0.9072379 1.000488 0.28561 1.000488 0.2944943 1.044068 0.2944945 1.373903 0.28561 1.373903 0.2528129 1.364925 0.252813 1.373903 0.28561 1.460565 0.2856102 1.460565 0.2528128 1.469512 0.2528128 1.460565 0.2528128 1.460565 0.2856102 1.460565 0.2140728 1.460565 0.2528128 1.469512 0.2528128 1.000488 0.2140725 1.044068 0.2140728 1.044068 0.2051816 1.505545 0.2856101 1.469512 0.2856102 1.469512 0.2944943 1.153734 0.2903351 1.048793 0.2903351 1.045883 0.2990664 1.553072 0.9265979 1.530928 0.9265979 1.530928 0.9357835 1.565234 0.9265977 1.558196 0.9265977 1.558196 0.9357835 1.530928 0.9265979 1.527945 0.9265979 1.527945 0.9357835 1.057892 0.01086807 1.053874 0.006297409 1.047357 0.01762789 1.045883 0.09480309 1.045883 0.1021202 1.055068 0.1021202 1.068732 0.05807965 1.062461 0.08306509 1.07595 0.08376377 1.128612 0.1931164 1.128612 0.2023019 1.15626 0.2023016 1.419383 0.9357835 1.419383 0.9265977 1.412345 0.9265977 1.621477 0.9247831 1.621477 0.9155975 1.566897 0.9155978 1.412345 0.9357835 1.412345 0.9265977 1.40003 0.9265977 1.505697 0.9155978 1.470259 0.9155978 1.470259 0.9247834 1.295579 4.88289e-4 1.272555 4.88297e-4 1.272555 0.2052192 1.318602 0.2944474 1.295579 0.2944474 1.295579 0.3205384 1.272555 0.3329195 1.272555 0.3452491 1.295579 0.3452492 1.318602 0.3205383 1.295579 0.3205384 1.295579 0.3329195 1.272555 0.3205384 1.272555 0.3329195 1.295579 0.3329195 1.945016 0.5964685 1.945016 0.5543156 1.920101 0.570132 1.906096 0.9521344 1.906096 0.9410116 1.884241 0.9410114 1.791454 0.9521344 1.862386 0.952134 1.862386 0.9410116 1.469512 0.3452002 1.505545 0.3452002 1.505545 0.3329566 1.884065 0.2143492 1.883715 0.2235527 1.918286 0.2235528 1.883715 0.2235527 1.883598 0.2327569 1.918287 0.2327569 1.957133 0.3294374 1.920264 0.3294375 1.920751 0.3386411 1.957133 0.3202335 1.920101 0.3202334 1.920264 0.3294375 1.272555 0.3452491 1.272555 0.3329195 1.188232 0.3329193 1.945016 0.7608169 1.945016 0.7516131 1.920101 0.7516131 1.08002 0.04160183 1.08002 0.05257523 1.123011 0.05257523 1.945016 0.6148759 1.945016 0.6056721 1.920101 0.6056721 1.920752 0.2143484 1.920263 0.223552 1.957133 0.2235522 1.061048 0.9326534 1.061048 0.9072378 1.051844 0.9072378 1.148526 0.9326536 1.157729 0.9326534 1.157729 0.907238 1.000488 0.3205851 1.044068 0.3205851 1.044068 0.2944945 1.044068 6.73867e-4 1.000488 6.73875e-4 1.000488 0.2051817 1.364925 0.252813 1.373903 0.2528129 1.373903 0.2140727 1.730731 0.9391972 1.944592 0.9391971 1.944592 0.8284353 1.000488 0.2528129 1.000488 0.28561 1.044068 0.28561 1.945016 0.7516131 1.945016 0.7424094 1.920101 0.7424094 1.883598 0.2327569 1.883598 0.36029 1.918286 0.36029 1.710524 0.4326251 1.626433 0.4326247 1.626433 0.4419283 1.505545 0.3329566 1.505545 0.3205853 1.469512 0.3205853 1.044068 0.2528129 1.053018 0.2528129 1.053018 0.2140728 1.179276 0.2140728 1.179276 0.2528129 1.188231 0.252813 1.318602 0.2856103 1.295579 0.2856099 1.295579 0.2944474 1.318602 0.2528129 1.295579 0.252813 1.295579 0.2856099 1.364925 0.2944475 1.364925 0.28561 1.318602 0.2856103 1.364925 0.252813 1.318602 0.2528129 1.318602 0.2856103 1.272555 0.2140727 1.272555 0.2052192 1.188232 0.2052192 1.295579 0.2140727 1.295579 0.252813 1.318602 0.2528129 1.272555 0.2140727 1.188232 0.2140728 1.188231 0.252813 1.318602 0.2052192 1.318603 4.88513e-4 1.295579 4.88289e-4 1.364925 0.2052192 1.364925 4.88281e-4 1.318603 4.88513e-4 1.505545 0.2528129 1.505545 0.2140728 1.469512 0.2140727 1.505545 0.2140728 1.505545 0.2051752 1.469512 0.2051753 1.469512 5.12323e-4 1.469512 0.2051753 1.505545 0.2051752 1.505545 0.2528129 1.469512 0.2528128 1.469512 0.2856102 1.730967 0.3348015 1.730967 0.5486626 1.881784 0.5486628 1.000488 0.2528129 1.044068 0.2528129 1.044068 0.2140728 1.730967 0.5486626 1.733877 0.5573942 1.878873 0.5573942 1.721999 0.831346 1.721999 0.9362868 1.730731 0.9391972 1.14343 0.01716881 1.147923 0.01234704 1.137722 0.007961034 1.152668 0.06678771 1.142777 0.05496656 1.136054 0.05899429 1.136949 0.01433765 1.137722 0.007961034 1.103101 0.006463944 1.152293 0.02071493 1.147923 0.01234704 1.14343 0.01716881 1.12823 0.0844019 1.141682 0.0840274 1.136054 0.05899429 1.446652 0.9357835 1.446652 0.9265977 1.424507 0.9265977 1.101071 0.1931164 1.101071 0.2023019 1.128612 0.2023019 1.07353 0.2023016 1.101071 0.2023019 1.101071 0.1931164 1.449634 0.9357835 1.449634 0.9265977 1.446652 0.9265977 1.554871 0.9247831 1.554871 0.9155978 1.541136 0.9155978 1.12823 0.0844019 1.102103 0.08445197 1.102014 0.09187269 1.102368 0.06344956 1.123577 0.06251293 1.122161 0.05621325 1.139571 0.02124476 1.14343 0.01716881 1.136949 0.01433765 1.067514 8.04474e-4 1.053874 0.006297409 1.057892 0.01086807 1.133425 0.0527479 1.136054 0.05899429 1.142777 0.05496656 1.13594 0.01979029 1.136949 0.01433765 1.102993 0.01307231 1.137722 0.007961034 1.138676 0.00206077 1.103204 4.88464e-4 1.145941 0.02213335 1.14343 0.01716881 1.139571 0.02124476 1.071551 0.05187094 1.068732 0.05807965 1.081175 0.06195604 1.15626 0.1844575 1.127641 0.1844576 1.128612 0.1931164 1.081175 0.06195604 1.07595 0.08376377 1.102103 0.08445197 1.138665 0.04879873 1.142777 0.05496656 1.14598 0.04982274 1.068847 0.01318633 1.102993 0.01307231 1.103101 0.006463944 1.48879 0.9357835 1.48879 0.9265977 1.454137 0.9265977 1.12989 0.1608373 1.125262 0.1680715 1.139076 0.1680715 1.149798 0.1758696 1.15626 0.1758696 1.15626 0.1666837 1.621477 0.9247831 1.631649 0.9247834 1.631649 0.9155975 1.07595 0.08376377 1.074652 0.0912249 1.102014 0.09187269 1.102368 0.06344956 1.102452 0.05688887 1.082787 0.05568909 1.059615 0.0207507 1.064993 0.02227306 1.066018 0.02002781 1.138676 0.00206077 1.137722 0.007961034 1.147923 0.01234704 1.06636 0.04771524 1.064468 0.04335635 1.058948 0.04857367 1.069677 0.01867198 1.102902 0.01896369 1.102993 0.01307231 1.074501 0.1844576 1.07353 0.1931163 1.101071 0.1931164 1.364925 0.3329192 1.318602 0.3329197 1.318602 0.3452491 1.918286 0.36029 1.883598 0.36029 1.883715 0.3694932 1.295579 0.2856099 1.272555 0.2856099 1.272555 0.2944474 1.906096 0.9410116 1.906096 0.9521344 1.942511 0.9521344 1.188232 0.3205384 1.272555 0.3205384 1.272555 0.2944474 1.318602 0.3329197 1.364925 0.3329192 1.364925 0.3205381 1.061048 0.9072378 1.061048 0.9326534 1.148526 0.9326536 1.920101 0.7871531 1.945016 0.8029695 1.945016 0.7608169 1.870277 0.7697482 1.71946 0.769748 1.71946 0.8119004 1.209085 0.9228498 1.166933 0.9072378 1.166933 0.9326535 1.188231 0.252813 1.179276 0.2528129 1.179276 0.28561 1.053018 0.28561 1.053018 0.2528129 1.044068 0.2528129 1.272555 0.2856099 1.188232 0.28561 1.188232 0.2944475 1.945016 0.6056721 1.945016 0.5964685 1.920101 0.5964685 1.364925 0.2052192 1.318602 0.2052192 1.318602 0.2140727 1.318602 0.2140727 1.318602 0.2528129 1.364925 0.252813 1.272555 0.2140727 1.295579 0.2140727 1.295579 0.205219 1.272555 4.88297e-4 1.188232 4.88337e-4 1.188232 0.2052192 1.272555 0.3329195 1.272555 0.3205384 1.188232 0.3205384 1.469512 0.3205853 1.505545 0.3205853 1.505545 0.2944943 1.867367 0.7610166 1.722371 0.7610161 1.71946 0.769748 1.062268 0.01583838 1.068847 0.01318633 1.068279 0.006764054 1.068732 0.05807965 1.06206 0.053842 1.051834 0.06548821 1.053269 0.01916384 1.059615 0.0207507 1.062268 0.01583838 1.424507 0.9357835 1.424507 0.9265977 1.419383 0.9265977 1.558196 0.9265977 1.553072 0.9265979 1.553072 0.9357835 1.389918 0.9247831 1.389918 0.9155975 1.379746 0.9155975 1.147923 0.01234704 1.152293 0.02071493 1.158206 0.01933556 1.139076 0.1680715 1.125262 0.1680715 1.12989 0.1753889 1.597833 0.9265977 1.577549 0.9265977 1.577549 0.9357835 1.470259 0.9155978 1.456524 0.9155978 1.456524 0.9247831 1.045883 0.09480309 1.059697 0.09480309 1.055069 0.08756864 1.052344 0.1758695 1.052344 0.1666837 1.045883 0.1666837 1.066018 0.02002781 1.069677 0.01867198 1.068847 0.01318633 1.123577 0.06251293 1.136054 0.05899429 1.133425 0.0527479 1.295579 0.2944474 1.272555 0.2944474 1.272555 0.3205384 1.158206 0.01933556 1.152293 0.02071493 1.152668 0.06678771 1.918286 0.3694939 1.918286 0.3786976 1.884066 0.3786978 1.156644 0.3412187 1.045883 0.3412187 1.045883 0.2990664 1.460565 0.2528128 1.373903 0.2528129 1.373903 0.2140727 1.428085 0.1316481 1.428085 0.1205881 1.463422 0.1205881 1.272555 0.2528129 1.272555 0.2856099 1.188232 0.28561 1.920101 0.7424094 1.920101 0.6148759 1.945016 0.6148759 1.432625 0.4419285 1.432625 0.4326248 1.475616 0.4326248 1.179276 0.28561 1.053018 0.28561 1.053018 0.2528129 1.000488 0.3205851 1.044068 0.3205851 1.044068 0.3329567 1.272555 0.2856099 1.272555 0.2528129 1.295579 0.252813 1.272555 0.2528129 1.272555 0.2140727 1.295579 0.2140727 1.449634 0.9265977 1.454137 0.9265977 1.454137 0.9357835 1.565234 0.9357835 1.565234 0.9265977 1.577549 0.9265977 1.444498 0.9247831 1.444498 0.9155978 1.456524 0.9155978 1.379746 0.9265977 1.40003 0.9265977 1.40003 0.9357835 1.047357 0.01762789 1.053269 0.01916384 1.051834 0.06548821 1.152293 0.02071493 1.152668 0.06678771 1.14598 0.04982274 1.071551 0.05187094 1.068732 0.05807965 1.06206 0.053842 1.068279 0.006764054 1.067514 8.04474e-4 1.103204 4.88464e-4 1.127641 0.1844576 1.128612 0.1931164 1.101071 0.1931164 1.064468 0.04335635 1.058948 0.04857367 1.059615 0.0207507 1.123577 0.06251293 1.12823 0.0844019 1.102103 0.08445197 1.523443 0.9357835 1.523443 0.9265977 1.527945 0.9265979 1.505697 0.9155978 1.541136 0.9155978 1.541137 0.9247834 1.48879 0.9357835 1.48879 0.9265977 1.523443 0.9265977 1.07353 0.1931163 1.07353 0.2023016 1.045883 0.2023016 1.389918 0.9247831 1.389918 0.9155975 1.444498 0.9155978 1.554871 0.9155978 1.566897 0.9155978 1.566898 0.9247831 1.053269 0.01916384 1.059615 0.0207507 1.058948 0.04857367 1.140609 0.0445531 1.14054 0.0235123 1.145941 0.02213335 1.045883 0.1844576 1.074501 0.1844576 1.07353 0.1931163 1.295579 0.205219 1.318602 0.2052192 1.318602 0.2140727 1.318602 0.3329197 1.318602 0.3452491 1.295579 0.3452492 1.884241 0.9410114 1.884241 0.9521344 1.862386 0.952134 1.920263 0.223552 1.957133 0.2235522 1.957133 0.2327558 1.318602 0.3205383 1.318602 0.2944474 1.364925 0.2944475 1.957133 0.3202335 1.920101 0.3202334 1.920101 0.2327558 1.157729 0.907238 1.166933 0.9072378 1.166933 0.9326535 1.044068 0.3329567 1.044068 0.3452001 1.000488 0.3452001 1.042641 0.9326536 1.000488 0.9326536 1.000488 0.92285 1.728519 0.6419227 1.710385 0.6419227 1.718715 0.6065858 1.053018 0.2528129 1.053018 0.2140728 1.179276 0.2140728 1.042641 0.9072379 1.051844 0.9072378 1.051845 0.9326536 1.000488 0.28561 1.044068 0.28561 1.044068 0.2944945 1.364925 0.252813 1.373903 0.2528129 1.373903 0.28561 1.373903 0.28561 1.373903 0.2528129 1.460565 0.2528128 1.469512 0.2528128 1.469512 0.2856102 1.460565 0.2856102 1.460565 0.2140728 1.469512 0.2140727 1.469512 0.2528128 1.044068 0.2051816 1.044068 0.2140728 1.000488 0.2140725 1.469512 0.2944943 1.469512 0.2856102 1.505545 0.2856101 1.156644 0.2990664 1.045883 0.2990664 1.048793 0.2903351 1.530928 0.9357835 1.530928 0.9265979 1.553072 0.9265979 1.558196 0.9357835 1.558196 0.9265977 1.565234 0.9265977 1.527945 0.9357835 1.527945 0.9265979 1.530928 0.9265979 1.057892 0.01086807 1.053269 0.01916384 1.047357 0.01762789 1.045883 0.09480309 1.059697 0.09480309 1.055068 0.1021202 1.07595 0.08376377 1.062461 0.08306509 1.068732 0.05807965 1.15626 0.2023016 1.128612 0.2023019 1.128612 0.1931164 1.412345 0.9265977 1.419383 0.9265977 1.419383 0.9357835 1.566897 0.9155978 1.621477 0.9155975 1.621477 0.9247831 1.40003 0.9265977 1.412345 0.9265977 1.412345 0.9357835 1.470259 0.9247834 1.470259 0.9155978 1.505697 0.9155978 1.295579 4.88289e-4 1.295579 0.205219 1.272555 0.2052192 1.295579 0.3205384 1.295579 0.2944474 1.318602 0.2944474 1.295579 0.3452492 1.272555 0.3452491 1.272555 0.3329195 1.318602 0.3205383 1.318602 0.3329197 1.295579 0.3329195 1.295579 0.3329195 1.272555 0.3329195 1.272555 0.3205384 1.945016 0.5964685 1.920101 0.5964685 1.920101 0.570132 1.906096 0.9521344 1.884241 0.9521344 1.884241 0.9410114 1.791454 0.9521344 1.791454 0.9410114 1.862386 0.9410116 1.469512 0.3452002 1.469512 0.3329566 1.505545 0.3329566 1.884065 0.2143492 1.918287 0.2143492 1.918286 0.2235528 1.883715 0.2235527 1.918286 0.2235528 1.918287 0.2327569 1.957133 0.3294374 1.957133 0.3386409 1.920751 0.3386411 1.957133 0.3202335 1.957133 0.3294374 1.920264 0.3294375 1.272555 0.3452491 1.188232 0.3452492 1.188232 0.3329193 1.920101 0.7516131 1.945016 0.7516131 1.945016 0.7608169 1.123011 0.05257523 1.08002 0.05257523 1.08002 0.04160183 1.945016 0.6148759 1.920101 0.6148759 1.920101 0.6056721 1.920752 0.2143484 1.957133 0.2143483 1.957133 0.2235522 1.051844 0.9072378 1.061048 0.9072378 1.061048 0.9326534 1.148526 0.9326536 1.148526 0.9072379 1.157729 0.907238 1.044068 0.2944945 1.044068 0.3205851 1.000488 0.3205851 1.000488 0.2051817 1.000488 6.73875e-4 1.044068 6.73867e-4 1.364925 0.252813 1.364925 0.2140727 1.373903 0.2140727 1.944592 0.8284353 1.944592 0.9391971 1.730731 0.9391972 1.000488 0.2528129 1.044068 0.2528129 1.044068 0.28561 1.945016 0.7516131 1.920101 0.7516131 1.920101 0.7424094 1.918286 0.36029 1.883598 0.36029 1.883598 0.2327569 1.710524 0.4326251 1.718715 0.4958242 1.626433 0.4419283 1.469512 0.3205853 1.505545 0.3205853 1.505545 0.3329566 1.044068 0.2528129 1.044068 0.2140728 1.053018 0.2140728 1.179276 0.2140728 1.188232 0.2140728 1.188231 0.252813 1.295579 0.2944474 1.295579 0.2856099 1.318602 0.2856103 1.295579 0.2856099 1.295579 0.252813 1.318602 0.2528129 1.364925 0.2944475 1.318602 0.2944474 1.318602 0.2856103 1.318602 0.2856103 1.318602 0.2528129 1.364925 0.252813 1.272555 0.2140727 1.188232 0.2140728 1.188232 0.2052192 1.295579 0.2140727 1.318602 0.2140727 1.318602 0.2528129 1.188231 0.252813 1.188232 0.2140728 1.272555 0.2140727 1.318602 0.2052192 1.295579 0.205219 1.295579 4.88289e-4 1.364925 0.2052192 1.318602 0.2052192 1.318603 4.88513e-4 1.469512 0.2140727 1.505545 0.2140728 1.505545 0.2528129 1.505545 0.2140728 1.469512 0.2140727 1.469512 0.2051753 1.505545 0.2051752 1.469512 0.2051753 1.469512 5.12323e-4 1.505545 0.2528129 1.505545 0.2856101 1.469512 0.2856102 1.881784 0.5486628 1.730967 0.5486626 1.730967 0.3348015 1.000488 0.2528129 1.000488 0.2140725 1.044068 0.2140728 1.730967 0.5486626 1.881784 0.5486628 1.878873 0.5573942 1.730731 0.9391972 1.721999 0.9362868 1.721999 0.831346 1.14343 0.01716881 1.136949 0.01433765 1.137722 0.007961034 1.152668 0.06678771 1.14918 0.07562226 1.136054 0.05899429 1.136949 0.01433765 1.102993 0.01307231 1.103101 0.006463944 1.152293 0.02071493 1.145941 0.02213335 1.14343 0.01716881 1.136054 0.05899429 1.141682 0.0840274 1.12823 0.0844019 1.424507 0.9265977 1.446652 0.9265977 1.446652 0.9357835 1.128612 0.2023019 1.101071 0.2023019 1.101071 0.1931164 1.101071 0.1931164 1.101071 0.2023019 1.07353 0.2023016 1.446652 0.9265977 1.449634 0.9265977 1.449634 0.9357835 1.541136 0.9155978 1.554871 0.9155978 1.554871 0.9247831 1.12823 0.0844019 1.129347 0.09187269 1.102014 0.09187269 1.102368 0.06344956 1.102452 0.05688887 1.122161 0.05621325 1.139571 0.02124476 1.13594 0.01979029 1.136949 0.01433765 1.067514 8.04474e-4 1.068279 0.006764054 1.057892 0.01086807 1.133425 0.0527479 1.138665 0.04879873 1.142777 0.05496656 1.13594 0.01979029 1.102902 0.01896369 1.102993 0.01307231 1.103204 4.88464e-4 1.138676 0.00206077 1.137722 0.007961034 1.145941 0.02213335 1.14054 0.0235123 1.139571 0.02124476 1.081175 0.06195604 1.068732 0.05807965 1.071551 0.05187094 1.15626 0.1844575 1.15626 0.1931163 1.128612 0.1931164 1.081175 0.06195604 1.102368 0.06344956 1.102103 0.08445197 1.138665 0.04879873 1.140609 0.0445531 1.14598 0.04982274 1.068847 0.01318633 1.068279 0.006764054 1.103101 0.006463944 1.454137 0.9265977 1.48879 0.9265977 1.48879 0.9357835 1.139076 0.1680715 1.125262 0.1680715 1.12989 0.1608373 1.149798 0.1758696 1.149798 0.1666839 1.15626 0.1666837 1.621477 0.9247831 1.621477 0.9155975 1.631649 0.9155975 1.07595 0.08376377 1.102103 0.08445197 1.102014 0.09187269 1.102368 0.06344956 1.081175 0.06195604 1.082787 0.05568909 1.059615 0.0207507 1.062268 0.01583838 1.066018 0.02002781 1.138676 0.00206077 1.152043 0.007921338 1.147923 0.01234704 1.06636 0.04771524 1.06206 0.053842 1.058948 0.04857367 1.069677 0.01867198 1.068847 0.01318633 1.102993 0.01307231 1.074501 0.1844576 1.101071 0.1844576 1.101071 0.1931164 1.364925 0.3329192 1.364925 0.3452492 1.318602 0.3452491 1.918286 0.36029 1.918286 0.3694939 1.883715 0.3694932 1.272555 0.2944474 1.272555 0.2856099 1.295579 0.2856099 1.906096 0.9410116 1.942511 0.9410114 1.942511 0.9521344 1.272555 0.2944474 1.272555 0.3205384 1.188232 0.3205384 1.318602 0.3329197 1.318602 0.3205383 1.364925 0.3205381 1.061048 0.9072378 1.148526 0.9072379 1.148526 0.9326536 1.920101 0.7871531 1.920101 0.7608169 1.945016 0.7608169 1.71946 0.8119004 1.71946 0.769748 1.870277 0.7697482 1.209085 0.9228498 1.209086 0.9326535 1.166933 0.9326535 1.188231 0.252813 1.188232 0.28561 1.179276 0.28561 1.053018 0.28561 1.044068 0.28561 1.044068 0.2528129 1.188232 0.2944475 1.188232 0.28561 1.272555 0.2856099 1.945016 0.6056721 1.920101 0.6056721 1.920101 0.5964685 1.364925 0.2052192 1.364925 0.2140727 1.318602 0.2140727 1.318602 0.2140727 1.364925 0.2140727 1.364925 0.252813 1.272555 0.2140727 1.272555 0.2052192 1.295579 0.205219 1.272555 4.88297e-4 1.272555 0.2052192 1.188232 0.2052192 1.272555 0.3329195 1.188232 0.3329193 1.188232 0.3205384 1.505545 0.2944943 1.505545 0.3205853 1.469512 0.3205853 1.71946 0.769748 1.722371 0.7610161 1.867367 0.7610166 1.062268 0.01583838 1.057892 0.01086807 1.068279 0.006764054 1.051834 0.06548821 1.06206 0.053842 1.068732 0.05807965 1.053269 0.01916384 1.057892 0.01086807 1.062268 0.01583838 1.419383 0.9265977 1.424507 0.9265977 1.424507 0.9357835 1.553072 0.9357835 1.553072 0.9265979 1.558196 0.9265977 1.389918 0.9247831 1.379746 0.9247834 1.379746 0.9155975 1.147923 0.01234704 1.152043 0.007921338 1.158206 0.01933556 1.139076 0.1680715 1.139076 0.1753889 1.12989 0.1753889 1.577549 0.9357835 1.577549 0.9265977 1.597833 0.9265977 1.456524 0.9247831 1.456524 0.9155978 1.470259 0.9155978 1.055069 0.08756864 1.059697 0.09480309 1.045883 0.09480309 1.052344 0.1758695 1.045883 0.1758695 1.045883 0.1666837 1.066018 0.02002781 1.062268 0.01583838 1.068847 0.01318633 1.133425 0.0527479 1.136054 0.05899429 1.123577 0.06251293 1.272555 0.3205384 1.272555 0.2944474 1.295579 0.2944474 1.158206 0.01933556 1.15839 0.07515925 1.152668 0.06678771 0.1602049 4.88286e-4 0.1602049 0.1149616 0.1656056 0.1149616 0.3668324 4.88286e-4 0.3795462 0.1296846 0.4252825 0.1296843 0.1602049 0.1149616 0.160205 0.1191003 0.1656055 0.1191003 0.718721 0.1367283 0.718721 0.2077418 0.8513208 0.18937 0.5584729 0.8715661 0.558473 0.8886547 0.6886763 0.8886547 0.122774 0.03978753 0.1267297 0.0226742 0.06735414 0.02267414 0.7187211 4.88286e-4 0.718721 0.1268674 0.8513209 0.1268674 0.9742742 0.475126 0.9995117 0.4751258 0.9995117 0.3395631 0.9742742 0.7152901 0.9995117 0.7152901 0.9995117 0.4839324 0.4301471 0.09963738 0.4301471 0.117868 0.4476855 0.1131566 0.7033466 0.1367283 0.718721 0.1367283 0.718721 0.1324492 0.9742742 0.4795293 0.9742742 0.4839326 0.9995117 0.4839324 0.1201953 0.6398431 0.1241632 0.6398431 0.1241632 0.6338987 0.9672788 0.8244635 0.9672788 0.8824383 0.9849687 0.8827466 0.9878022 0.1162673 0.9589474 0.1162674 0.9589475 0.1224743 0.4394726 0.4166052 0.46257 0.4166054 0.46257 0.2874245 0.9589475 0.1286842 0.9589475 0.3377504 0.9878022 0.3377475 0.1656056 0.123239 0.1602049 0.123239 0.160205 0.1693082 0.9589474 0.1162674 0.9878022 0.1162673 0.9878022 0.08591735 0.9507004 0.7686162 0.9507007 0.7764334 0.9672788 0.7764334 0.9589475 0.1224743 0.9589475 0.1286842 0.9878022 0.1286842 0.1656055 0.1191003 0.160205 0.1191003 0.1602049 0.123239 4.8841e-4 0.9054236 0.2079482 0.9054236 4.88282e-4 0.7880615 0.2079482 0.9054236 0.2121256 0.9040311 0.2135181 0.8998538 0.2135179 0.7880615 0.2079482 0.9054236 0.2135181 0.8998538 0.7033466 4.88286e-4 0.7033464 0.1268675 0.718721 0.1268674 0.851321 0.2727802 0.7187211 0.2598316 0.718721 0.3340762 0.04630947 0.2041161 0.04594987 0.2091332 0.09486085 0.2091332 0.5634874 0.9075481 0.6936855 0.9075482 0.6936855 0.8904688 0.1370818 0.1372556 0.1542612 0.1406455 0.1542612 0.08812946 0.5634765 0.8697519 0.6936799 0.8697519 0.6936799 0.8526635 0.9507005 0.554348 0.9507004 0.7686162 0.9672788 0.7686162 0.1102058 0.9344678 0.07420951 0.9344678 0.07455897 0.9395559 0.158074 0.19422 0.1752538 0.1976141 0.1752538 0.1711225 0.9698835 0.03194242 0.9878022 0.0278356 0.9878022 0.001010596 0.4497116 0.08430391 0.4321468 0.07959276 0.4321468 0.09782314 0.718721 0.1324492 0.718721 0.1268674 0.7033464 0.1268675 0.3667389 0.1830862 0.4183209 0.1830862 0.4183209 0.1695669 0.1241632 0.6338987 0.1241632 0.6398431 0.1281312 0.6398431 0.9672788 0.7764334 0.9507007 0.7764334 0.9507007 0.7841923 0.8513209 0.1312991 0.8513209 0.1268674 0.718721 0.1268674 5.41001e-4 0.9344677 8.27478e-4 0.939536 0.0719918 0.939536 0.9672788 0.8244635 0.9672788 0.7841923 0.9507007 0.7841923 0.9507007 0.7841923 0.9507004 0.9089362 0.9672788 0.8244635 0.9507004 0.9089362 0.9672788 0.9092137 0.9672788 0.8824383 0.558473 0.8697519 0.5634765 0.8697519 0.5634765 0.8526635 0.6886763 0.8715661 0.6886763 0.8886547 0.6936799 0.8886547 0.3343058 0.6398431 0.3343058 0.6338987 0.1281311 0.6338989 0.718721 0.1367283 0.8513209 0.1367283 0.8513209 0.1312991 0.9742742 0.475126 0.9742742 0.4795293 0.9995117 0.4795292 0.9698835 0.03194242 0.9589475 5.04342e-4 0.9589474 0.1162674 0.7033466 0.1367283 0.7033466 0.3603313 0.718721 0.2077418 0.5584729 0.9075482 0.5634874 0.9075481 0.5634874 0.8904688 4.88281e-4 0.6398431 0.1201953 0.6398431 0.1201952 0.6338989 1.160205 4.88286e-4 1.165606 4.88286e-4 1.165606 0.1149616 1.366832 4.88286e-4 1.437996 4.88286e-4 1.425282 0.1296843 1.165606 0.1191003 1.160205 0.1191003 1.160205 0.1149616 1.851321 0.18937 1.718721 0.2077418 1.718721 0.1367283 1.558473 0.8715661 1.688676 0.8715661 1.688676 0.8886547 1.122774 0.03978753 1.071192 0.03978765 1.067354 0.02267414 1.718721 4.88286e-4 1.851321 4.88286e-4 1.851321 0.1268674 1.999512 0.3395631 1.999512 0.4751258 1.974274 0.475126 1.999512 0.4839324 1.999512 0.7152901 1.974274 0.7152901 1.430147 0.09963738 1.447686 0.09963732 1.447685 0.1131566 1.703347 0.1367283 1.703346 0.1322978 1.718721 0.1324492 1.999512 0.4839324 1.974274 0.4839326 1.974274 0.4795293 1.124163 0.6338987 1.124163 0.6398431 1.120195 0.6398431 1.984969 0.8827466 1.967279 0.8824383 1.967279 0.8244635 1.987802 0.1162673 1.987802 0.1224736 1.958947 0.1224743 1.439473 0.4166052 1.426923 0.2874243 1.46257 0.2874245 1.958947 0.1286842 1.987802 0.1286842 1.987802 0.3377475 1.165606 0.123239 1.165606 0.1693081 1.160205 0.1693082 1.958947 0.1162674 1.969421 0.08381986 1.987802 0.08591735 1.967279 0.7764334 1.950701 0.7764334 1.9507 0.7686162 1.987802 0.1286842 1.958947 0.1286842 1.958947 0.1224743 1.165606 0.1191003 1.165606 0.123239 1.160205 0.123239 1.212126 0.9040311 1.207948 0.9054236 1.213518 0.8998538 1.207948 0.9054236 1.000488 0.9054236 1.000488 0.7880615 1.213518 0.7880615 1.207948 0.9054236 1.000488 0.7880615 1.718721 0.1268674 1.703346 0.1268675 1.703346 4.88286e-4 1.851321 0.2727802 1.851321 0.3212934 1.718721 0.3340762 1.046309 0.2041161 1.09455 0.2041161 1.094861 0.2091332 1.693686 0.8904688 1.693686 0.9075482 1.563487 0.9075481 1.137082 0.1372556 1.137082 0.09151941 1.154261 0.08812946 1.69368 0.8526635 1.69368 0.8697519 1.563477 0.8697519 1.9507 0.554348 1.967279 0.5542747 1.967279 0.7686162 1.110206 0.9344678 1.110206 0.9395559 1.074559 0.9395559 1.158074 0.19422 1.158074 0.1711224 1.175254 0.1711225 1.969883 0.03194242 1.958947 5.04342e-4 1.987802 0.001010596 1.432147 0.09782314 1.432147 0.07959276 1.449712 0.08430391 1.703346 0.1268675 1.718721 0.1268674 1.718721 0.1324492 1.418321 0.1695669 1.418321 0.1830862 1.366739 0.1830862 1.124163 0.6338987 1.128131 0.6338989 1.128131 0.6398431 1.967279 0.7764334 1.967279 0.7841923 1.950701 0.7841923 1.718721 0.1268674 1.851321 0.1268674 1.851321 0.1312991 1.000541 0.9344677 1.072278 0.934468 1.071992 0.939536 1.950701 0.7841923 1.967279 0.7841923 1.967279 0.8244635 1.967279 0.8824383 1.967279 0.9092137 1.9507 0.9089362 1.950701 0.7841923 1.967279 0.8244635 1.9507 0.9089362 1.563477 0.8526635 1.563477 0.8697519 1.558473 0.8697519 1.688676 0.8715661 1.69368 0.8715661 1.69368 0.8886547 1.334306 0.6398431 1.128131 0.6398431 1.128131 0.6338989 1.718721 0.1367283 1.718721 0.1324492 1.851321 0.1312991 1.999512 0.4795292 1.974274 0.4795293 1.974274 0.475126 1.969883 0.03194242 1.969421 0.08381986 1.958947 0.1162674 1.718721 0.2077418 1.703346 0.3603313 1.703347 0.1367283 1.563487 0.8904688 1.563487 0.9075481 1.558473 0.9075482 1.000488 0.6398431 1.000488 0.6338987 1.120195 0.6338989 1.160205 4.88286e-4 1.165606 4.88286e-4 1.165606 0.1149616 1.366832 4.88286e-4 1.437996 4.88286e-4 1.425282 0.1296843 1.165606 0.1191003 1.160205 0.1191003 1.160205 0.1149616 1.851321 0.18937 1.718721 0.2077418 1.718721 0.1367283 1.558473 0.8715661 1.688676 0.8715661 1.688676 0.8886547 1.122774 0.03978753 1.071192 0.03978765 1.067354 0.02267414 1.718721 4.88286e-4 1.851321 4.88286e-4 1.851321 0.1268674 1.999512 0.3395631 1.999512 0.4751258 1.974274 0.475126 1.999512 0.4839324 1.999512 0.7152901 1.974274 0.7152901 1.430147 0.09963738 1.447686 0.09963732 1.447685 0.1131566 1.703347 0.1367283 1.703346 0.1322978 1.718721 0.1324492 1.999512 0.4839324 1.974274 0.4839326 1.974274 0.4795293 1.124163 0.6338987 1.124163 0.6398431 1.120195 0.6398431 1.984969 0.8827466 1.967279 0.8824383 1.967279 0.8244635 1.987802 0.1162673 1.987802 0.1224736 1.958947 0.1224743 1.439473 0.4166052 1.426923 0.2874243 1.46257 0.2874245 1.958947 0.1286842 1.987802 0.1286842 1.987802 0.3377475 1.165606 0.123239 1.165606 0.1693081 1.160205 0.1693082 1.958947 0.1162674 1.969421 0.08381986 1.987802 0.08591735 1.967279 0.7764334 1.950701 0.7764334 1.9507 0.7686162 1.987802 0.1286842 1.958947 0.1286842 1.958947 0.1224743 1.165606 0.1191003 1.165606 0.123239 1.160205 0.123239 1.212126 0.9040311 1.207948 0.9054236 1.213518 0.8998538 1.207948 0.9054236 1.000488 0.9054236 1.000488 0.7880615 1.213518 0.7880615 1.207948 0.9054236 1.000488 0.7880615 1.718721 0.1268674 1.703346 0.1268675 1.703346 4.88286e-4 1.851321 0.2727802 1.851321 0.3212934 1.718721 0.3340762 1.046309 0.2041161 1.09455 0.2041161 1.094861 0.2091332 1.693686 0.8904688 1.693686 0.9075482 1.563487 0.9075481 1.137082 0.1372556 1.137082 0.09151941 1.154261 0.08812946 1.69368 0.8526635 1.69368 0.8697519 1.563477 0.8697519 1.9507 0.554348 1.967279 0.5542747 1.967279 0.7686162 1.110206 0.9344678 1.110206 0.9395559 1.074559 0.9395559 1.158074 0.19422 1.158074 0.1711224 1.175254 0.1711225 1.969883 0.03194242 1.958947 5.04342e-4 1.987802 0.001010596 1.432147 0.09782314 1.432147 0.07959276 1.449712 0.08430391 1.703346 0.1268675 1.718721 0.1268674 1.718721 0.1324492 1.418321 0.1695669 1.418321 0.1830862 1.366739 0.1830862 1.124163 0.6338987 1.128131 0.6338989 1.128131 0.6398431 1.967279 0.7764334 1.967279 0.7841923 1.950701 0.7841923 1.718721 0.1268674 1.851321 0.1268674 1.851321 0.1312991 1.000541 0.9344677 1.072278 0.934468 1.071992 0.939536 1.950701 0.7841923 1.967279 0.7841923 1.967279 0.8244635 1.967279 0.8824383 1.967279 0.9092137 1.9507 0.9089362 1.950701 0.7841923 1.967279 0.8244635 1.9507 0.9089362 1.563477 0.8526635 1.563477 0.8697519 1.558473 0.8697519 1.688676 0.8715661 1.69368 0.8715661 1.69368 0.8886547 1.334306 0.6398431 1.128131 0.6398431 1.128131 0.6338989 1.718721 0.1367283 1.718721 0.1324492 1.851321 0.1312991 1.999512 0.4795292 1.974274 0.4795293 1.974274 0.475126 1.969883 0.03194242 1.969421 0.08381986 1.958947 0.1162674 1.718721 0.2077418 1.703346 0.3603313 1.703347 0.1367283 1.563487 0.8904688 1.563487 0.9075481 1.558473 0.9075482 1.000488 0.6398431 1.000488 0.6338987 1.120195 0.6338989 1.160205 4.88286e-4 1.160205 0.1149616 1.165606 0.1149616 1.366832 4.88286e-4 1.379546 0.1296846 1.425282 0.1296843 1.160205 0.1149616 1.160205 0.1191003 1.165606 0.1191003 1.718721 0.1367283 1.718721 0.2077418 1.851321 0.18937 1.558473 0.8715661 1.558473 0.8886547 1.688676 0.8886547 1.122774 0.03978753 1.12673 0.0226742 1.067354 0.02267414 1.718721 4.88286e-4 1.718721 0.1268674 1.851321 0.1268674 1.974274 0.475126 1.999512 0.4751258 1.999512 0.3395631 1.974274 0.7152901 1.999512 0.7152901 1.999512 0.4839324 1.430147 0.09963738 1.430147 0.117868 1.447685 0.1131566 1.703347 0.1367283 1.718721 0.1367283 1.718721 0.1324492 1.974274 0.4795293 1.974274 0.4839326 1.999512 0.4839324 1.120195 0.6398431 1.124163 0.6398431 1.124163 0.6338987 1.967279 0.8244635 1.967279 0.8824383 1.984969 0.8827466 1.987802 0.1162673 1.958947 0.1162674 1.958947 0.1224743 1.439473 0.4166052 1.46257 0.4166054 1.46257 0.2874245 1.958947 0.1286842 1.958947 0.3377504 1.987802 0.3377475 1.165606 0.123239 1.160205 0.123239 1.160205 0.1693082 1.958947 0.1162674 1.987802 0.1162673 1.987802 0.08591735 1.9507 0.7686162 1.950701 0.7764334 1.967279 0.7764334 1.958947 0.1224743 1.958947 0.1286842 1.987802 0.1286842 1.165606 0.1191003 1.160205 0.1191003 1.160205 0.123239 1.000488 0.9054236 1.207948 0.9054236 1.000488 0.7880615 1.207948 0.9054236 1.212126 0.9040311 1.213518 0.8998538 1.213518 0.7880615 1.207948 0.9054236 1.213518 0.8998538 1.703346 4.88286e-4 1.703346 0.1268675 1.718721 0.1268674 1.851321 0.2727802 1.718721 0.2598316 1.718721 0.3340762 1.046309 0.2041161 1.04595 0.2091332 1.094861 0.2091332 1.563487 0.9075481 1.693686 0.9075482 1.693686 0.8904688 1.137082 0.1372556 1.154261 0.1406455 1.154261 0.08812946 1.563477 0.8697519 1.69368 0.8697519 1.69368 0.8526635 1.9507 0.554348 1.9507 0.7686162 1.967279 0.7686162 1.110206 0.9344678 1.07421 0.9344678 1.074559 0.9395559 1.158074 0.19422 1.175254 0.1976141 1.175254 0.1711225 1.969883 0.03194242 1.987802 0.0278356 1.987802 0.001010596 1.449712 0.08430391 1.432147 0.07959276 1.432147 0.09782314 1.718721 0.1324492 1.718721 0.1268674 1.703346 0.1268675 1.366739 0.1830862 1.418321 0.1830862 1.418321 0.1695669 1.124163 0.6338987 1.124163 0.6398431 1.128131 0.6398431 1.967279 0.7764334 1.950701 0.7764334 1.950701 0.7841923 1.851321 0.1312991 1.851321 0.1268674 1.718721 0.1268674 1.000541 0.9344677 1.000827 0.939536 1.071992 0.939536 1.967279 0.8244635 1.967279 0.7841923 1.950701 0.7841923 1.950701 0.7841923 1.9507 0.9089362 1.967279 0.8244635 1.9507 0.9089362 1.967279 0.9092137 1.967279 0.8824383 1.558473 0.8697519 1.563477 0.8697519 1.563477 0.8526635 1.688676 0.8715661 1.688676 0.8886547 1.69368 0.8886547 1.334306 0.6398431 1.334306 0.6338987 1.128131 0.6338989 1.718721 0.1367283 1.851321 0.1367283 1.851321 0.1312991 1.974274 0.475126 1.974274 0.4795293 1.999512 0.4795292 1.969883 0.03194242 1.958947 5.04342e-4 1.958947 0.1162674 1.703347 0.1367283 1.703346 0.3603313 1.718721 0.2077418 1.558473 0.9075482 1.563487 0.9075481 1.563487 0.8904688 1.000488 0.6398431 1.120195 0.6398431 1.120195 0.6338989 - + - - + + - - - - -

106 0 216 107 1 0 110 2 1 110 3 1 111 4 215 106 5 216 98 6 208 99 7 2 14 8 3 14 9 3 11 10 207 98 11 208 110 12 1 107 13 0 108 14 209 108 15 209 109 16 210 110 17 1 99 18 2 100 19 217 10 20 218 10 21 218 14 22 3 99 23 2 4 24 4 17 25 5 15 26 219 15 27 219 3 28 220 4 29 4 5 30 211 16 31 212 17 32 5 17 33 5 4 34 4 5 35 211 17 36 5 14 37 3 10 38 218 10 39 218 15 40 219 17 41 5 16 42 212 11 43 207 14 44 3 14 45 3 17 46 5 16 47 212 8 48 213 0 49 214 1 50 6 1 51 6 12 52 7 8 53 213 1 54 6 2 55 221 6 56 222 6 57 222 12 58 7 1 59 6 0 60 214 8 61 213 21 62 8 21 63 8 20 64 9 0 65 214 495 66 11 496 67 12 23 68 13 23 69 13 24 70 10 495 71 11 33 72 25 18 73 26 20 74 27 33 75 25 20 76 27 21 77 31 33 78 25 21 79 31 22 80 32 22 81 32 28 82 33 34 83 34 34 84 34 33 85 25 22 86 32 28 87 33 27 88 35 35 89 36 35 90 36 34 91 34 28 92 33 27 93 35 26 94 37 32 95 38 32 96 38 35 97 36 27 98 35 32 99 38 26 100 37 29 101 39 29 102 39 31 103 40 32 104 38 31 105 40 29 106 39 25 107 41 25 108 41 30 109 42 31 110 40 38 111 15 117 112 16 118 113 17 118 114 17 39 115 14 38 116 15 42 117 18 6 118 222 2 119 221 2 120 221 41 121 19 42 122 18 48 123 43 44 124 44 47 125 45 47 126 45 49 127 46 48 128 43 49 129 46 47 130 45 43 131 47 43 132 47 50 133 48 49 134 46 51 135 55 36 136 56 38 137 57 51 138 55 38 139 57 39 140 58 51 141 55 39 142 58 40 143 59 40 144 59 46 145 60 52 146 61 52 147 61 51 148 55 40 149 59 46 150 60 45 151 62 53 152 63 53 153 63 52 154 61 46 155 60 45 156 62 44 157 44 48 158 43 48 159 43 53 160 63 45 161 62 56 162 20 11 163 207 16 164 212 16 165 212 57 166 21 56 167 20 57 168 21 16 169 212 5 170 211 5 171 211 58 172 22 57 173 21 63 174 24 116 175 49 122 176 50 122 177 50 62 178 23 63 179 24 69 180 67 68 181 68 61 182 69 61 183 69 67 184 70 69 185 67 65 186 71 70 187 72 69 188 67 69 189 67 67 190 70 65 191 71 64 192 73 71 193 74 70 194 72 70 195 72 65 196 71 64 197 73 66 198 75 72 199 76 71 200 74 71 201 74 64 202 73 66 203 75 59 204 77 73 205 78 72 206 76 72 207 76 66 208 75 59 209 77 313 210 52 119 211 53 78 212 54 78 213 54 77 214 51 313 215 52 119 216 53 315 217 79 76 218 80 76 219 80 78 220 54 119 221 53 81 222 81 80 223 82 15 224 219 15 225 219 10 226 218 81 227 81 3 228 220 15 229 219 80 230 82 80 231 82 83 232 83 3 233 220 85 234 90 88 235 91 89 236 92 89 237 92 87 238 93 85 239 90 90 240 94 88 241 91 85 242 90 85 243 90 84 244 95 90 245 94 86 246 96 91 247 97 90 248 94 90 249 94 84 250 95 86 251 96 92 252 98 91 253 97 86 254 96 86 255 96 79 256 99 92 257 98 87 258 93 89 259 92 93 260 100 93 261 100 82 262 101 87 263 93 495 264 11 24 265 10 25 266 85 25 267 85 568 268 84 495 269 11 23 270 103 19 271 104 30 272 42 24 273 102 23 274 103 30 275 42 24 276 102 30 277 42 25 278 41 30 279 29 19 280 30 18 281 64 18 282 64 33 283 28 30 284 29 44 285 87 104 286 88 105 287 89 105 288 89 47 289 86 44 290 87 41 291 106 37 292 107 50 293 48 42 294 105 41 295 106 50 296 48 42 297 105 50 298 48 43 299 47 36 300 65 51 301 66 50 302 111 50 303 111 37 304 112 36 305 65 67 306 114 123 307 115 573 308 116 573 309 116 97 310 117 67 311 114 63 312 109 62 313 110 60 314 126 54 315 108 63 316 109 60 317 126 68 318 68 54 319 108 60 320 126 68 321 68 60 322 126 61 323 69 56 324 127 57 325 128 58 326 129 56 327 127 58 328 129 55 329 130 56 330 127 55 331 130 73 332 78 56 333 127 73 334 78 59 335 77 68 336 113 73 337 139 55 338 140 55 339 140 54 340 141 68 341 113 116 342 177 63 343 178 54 344 188 54 345 188 952 346 1447 116 347 177 100 348 217 82 349 118 81 350 81 81 351 81 10 352 218 100 353 217 77 354 131 78 355 132 76 356 133 79 357 99 77 358 131 76 359 133 92 360 98 79 361 99 76 362 133 92 363 98 76 364 133 75 365 134 74 366 142 93 367 143 92 368 144 92 369 144 75 370 145 74 371 142 83 372 135 80 373 136 81 374 137 83 375 135 81 376 137 82 377 101 83 378 135 82 379 101 93 380 100 83 381 135 93 382 100 74 383 138 60 384 120 62 385 23 122 386 50 122 387 50 581 388 119 60 389 120 55 390 189 58 391 190 5 392 191 3 393 192 83 394 193 74 395 194 5 396 191 3 397 192 74 398 194 55 399 189 5 400 191 74 401 194 5 402 191 4 403 195 3 404 192 55 405 189 74 406 194 578 407 176 75 408 196 76 409 197 315 410 198 315 411 198 115 412 199 75 413 196 27 414 122 95 415 123 94 416 124 94 417 124 26 418 121 27 419 122 94 420 124 95 421 123 64 422 125 64 423 125 65 424 151 94 425 124 22 426 153 109 427 210 108 428 209 108 429 209 28 430 152 22 431 153 11 432 207 56 433 20 59 434 154 59 435 154 98 436 208 11 437 207 64 438 125 95 439 123 96 440 156 96 441 156 66 442 155 64 443 125 96 444 156 95 445 123 27 446 122 27 447 122 28 448 152 96 449 156 26 450 121 94 451 124 97 452 117 97 453 117 29 454 157 26 455 121 97 456 117 94 457 124 65 458 151 65 459 151 67 460 114 97 461 117 61 462 158 586 463 159 123 464 115 123 465 115 67 466 114 61 467 158 29 468 157 587 469 160 568 470 84 568 471 84 25 472 85 29 473 157 66 474 155 101 475 161 98 476 208 98 477 208 59 478 154 66 479 155 101 480 161 102 481 162 99 482 2 99 483 2 98 484 208 101 485 161 102 486 162 103 487 223 100 488 217 100 489 217 99 490 2 102 491 162 103 492 223 87 493 163 82 494 118 82 495 118 100 496 217 103 497 223 66 498 155 96 499 156 9 500 164 9 501 164 101 502 161 66 503 155 9 504 164 13 505 179 102 506 162 102 507 162 101 508 161 9 509 164 13 510 179 7 511 224 103 512 223 103 513 223 102 514 162 13 515 179 104 516 88 85 517 180 87 518 163 87 519 163 105 520 89 104 521 88 44 522 87 45 523 181 112 524 182 112 525 182 104 526 88 44 527 87 112 528 182 84 529 183 85 530 180 85 531 180 104 532 88 112 533 182 7 534 224 105 535 89 87 536 163 87 537 163 103 538 223 7 539 224 106 540 216 111 541 215 43 542 184 43 543 184 47 544 86 106 545 216 105 546 89 7 547 224 106 548 216 106 549 216 47 550 86 105 551 89 7 552 224 13 553 179 107 554 0 107 555 0 106 556 216 7 557 224 107 558 0 13 559 179 9 560 164 9 561 164 108 562 209 107 563 0 28 564 152 108 565 209 9 566 164 9 567 164 96 568 156 28 569 152 22 570 153 21 571 8 8 572 213 8 573 213 109 574 210 22 575 153 109 576 210 8 577 213 12 578 7 12 579 7 110 580 1 109 581 210 12 582 7 6 583 222 111 584 215 111 585 215 110 586 1 12 587 7 6 588 222 42 589 18 43 590 184 43 591 184 111 592 215 6 593 222 120 594 186 354 595 187 113 596 200 113 597 200 46 598 185 120 599 186 313 600 52 77 601 51 79 602 202 79 603 202 121 604 201 313 605 52 84 606 183 112 607 182 113 608 200 113 609 200 86 610 203 84 611 183 113 612 200 112 613 182 45 614 181 45 615 181 46 616 185 113 617 200 40 618 204 114 619 205 120 620 186 120 621 186 46 622 185 40 623 204 40 624 204 39 625 14 118 626 17 118 627 17 114 628 205 40 629 204 86 630 203 356 631 206 121 632 201 121 633 201 79 634 202 86 635 203 86 636 203 113 637 200 354 638 187 354 639 187 356 640 206 86 641 203 60 642 120 581 643 119 586 644 159 586 645 159 61 646 158 60 647 120 29 648 157 97 649 117 573 650 116 573 651 116 587 652 160 29 653 157 74 654 194 75 655 196 578 656 176 578 657 176 54 658 188 55 659 189 75 660 196 115 661 199 578 662 176 69 663 146 72 664 147 73 665 139 73 666 139 68 667 113 69 668 146 70 669 148 71 670 149 72 671 147 72 672 147 69 673 146 70 674 148 35 675 165 32 676 166 31 677 167 31 678 167 34 679 150 35 680 165 34 681 150 31 682 167 30 683 29 30 684 29 33 685 28 34 686 150 52 687 168 49 688 169 50 689 111 50 690 111 51 691 66 52 692 168 53 693 170 48 694 171 49 695 169 49 696 169 52 697 168 53 698 170 89 699 172 91 700 173 92 701 144 92 702 144 93 703 143 89 704 172 88 705 174 90 706 175 91 707 173 91 708 173 89 709 172 88 710 174 126 711 229 127 712 230 944 713 228 944 714 228 125 715 226 126 716 229 124 717 225 943 718 227 127 719 230 127 720 230 126 721 229 124 722 225 131 723 243 134 724 246 133 725 245 133 726 245 132 727 244 131 728 243 190 729 248 187 730 247 136 731 250 136 732 250 135 733 249 190 734 248 137 735 251 140 736 254 139 737 253 139 738 253 138 739 252 137 740 251 141 741 255 144 742 258 143 743 257 143 744 257 142 745 256 141 746 255 132 747 244 141 748 255 142 749 256 142 750 256 131 751 243 132 752 244 199 753 241 137 754 251 138 755 252 138 756 252 178 757 259 199 758 241 139 759 253 140 760 254 133 761 245 133 762 245 134 763 246 139 764 253 144 765 258 135 766 249 136 767 250 136 768 250 143 769 257 144 770 258 147 771 262 146 772 261 145 773 260 145 774 260 148 775 263 147 776 262 150 777 265 149 778 264 152 779 267 152 780 267 151 781 266 150 782 265 129 783 238 128 784 236 153 785 268 153 786 268 154 787 269 129 788 238 156 789 271 155 790 270 210 791 237 210 792 237 179 793 272 156 794 271 159 795 275 158 796 274 157 797 273 157 798 273 160 799 276 159 800 275 163 801 279 162 802 278 161 803 277 161 804 277 164 805 280 163 806 279 154 807 269 153 808 268 165 809 281 165 810 281 166 811 282 154 812 269 168 813 234 167 814 233 170 815 235 170 816 235 169 817 285 168 818 234 170 819 286 167 820 283 171 821 287 171 822 287 172 823 288 170 824 286 148 825 263 145 826 260 173 827 289 173 828 289 174 829 290 148 830 263 172 831 288 171 832 287 149 833 264 149 834 264 150 835 265 172 836 288 130 837 240 180 838 291 162 839 278 162 840 278 163 841 279 130 842 240 160 843 276 157 844 273 231 845 292 231 846 292 181 847 239 160 848 276 151 849 266 152 850 267 158 851 274 158 852 274 159 853 275 151 854 266 164 855 280 161 856 277 146 857 261 146 858 261 147 859 262 164 860 280 176 861 294 175 862 293 155 863 270 155 864 270 156 865 271 176 866 294 174 867 290 173 868 289 175 869 293 175 870 293 176 871 294 174 872 290 132 873 244 133 874 245 152 875 267 152 876 267 149 877 264 132 878 244 134 879 246 131 880 243 145 881 260 145 882 260 146 883 261 134 884 246 182 885 242 190 886 248 135 887 249 135 888 249 177 889 295 182 890 242 155 891 270 136 892 250 187 893 247 187 894 247 210 895 237 155 896 270 138 897 252 139 898 253 161 899 277 161 900 277 162 901 278 138 902 252 140 903 254 137 904 251 157 905 273 157 906 273 158 907 274 140 908 254 142 909 256 143 910 257 175 911 293 175 912 293 173 913 289 142 914 256 131 915 243 142 916 256 173 917 289 173 918 289 145 919 260 131 920 243 141 921 255 132 922 244 149 923 264 149 924 264 171 925 287 141 926 255 178 927 259 138 928 252 162 929 278 162 930 278 180 931 291 178 932 259 157 933 273 137 934 251 199 935 241 199 936 241 231 937 292 157 938 273 161 939 277 139 940 253 134 941 246 134 942 246 146 943 261 161 944 277 152 945 267 133 946 245 140 947 254 140 948 254 158 949 274 152 950 267 143 951 257 136 952 250 155 953 270 155 954 270 175 955 293 143 956 257 144 957 258 171 958 287 177 959 295 165 960 231 168 961 234 169 962 285 169 963 285 166 964 232 165 965 231 128 966 236 182 967 242 177 968 295 177 969 295 153 970 268 128 971 236 153 972 268 177 973 295 168 974 284 168 975 284 165 976 281 153 977 268 177 978 295 135 979 249 144 980 258 144 981 258 141 982 255 171 983 287 167 984 283 168 985 284 177 986 295 177 987 295 171 988 287 167 989 283 183 990 296 186 991 299 185 992 298 185 993 298 184 994 297 183 995 296 190 996 303 189 997 302 188 998 301 188 999 301 187 1000 300 190 1001 303 191 1002 304 194 1003 307 193 1004 306 193 1005 306 192 1006 305 191 1007 304 195 1008 308 198 1009 311 197 1010 310 197 1011 310 196 1012 309 195 1013 308 186 1014 299 183 1015 296 198 1016 311 198 1017 311 195 1018 308 186 1019 299 199 1020 312 178 1021 313 194 1022 307 194 1023 307 191 1024 304 199 1025 312 193 1026 306 184 1027 297 185 1028 298 185 1029 298 192 1030 305 193 1031 306 196 1032 309 197 1033 310 188 1034 301 188 1035 301 189 1036 302 196 1037 309 202 1038 316 201 1039 315 200 1040 314 200 1041 314 203 1042 317 202 1043 316 207 1044 321 206 1045 320 205 1046 319 205 1047 319 204 1048 318 207 1049 321 129 1050 324 209 1051 323 208 1052 322 208 1053 322 128 1054 325 129 1055 324 211 1056 328 179 1057 327 210 1058 326 210 1059 326 212 1060 329 211 1061 328 215 1062 332 214 1063 331 213 1064 330 213 1065 330 216 1066 333 215 1067 332 219 1068 336 218 1069 335 217 1070 334 217 1071 334 220 1072 337 219 1073 336 209 1074 323 222 1075 339 221 1076 338 221 1077 338 208 1078 322 209 1079 323 226 1080 343 225 1081 342 224 1082 341 224 1083 341 223 1084 340 226 1085 343 224 1086 346 228 1087 345 227 1088 344 227 1089 344 223 1090 347 224 1091 346 201 1092 315 230 1093 349 229 1094 348 229 1095 348 200 1096 314 201 1097 315 228 1098 345 207 1099 321 204 1100 318 204 1101 318 227 1102 344 228 1103 345 130 1104 350 219 1105 336 220 1106 337 220 1107 337 180 1108 351 130 1109 350 214 1110 331 181 1111 353 231 1112 352 231 1113 352 213 1114 330 214 1115 331 206 1116 320 215 1117 332 216 1118 333 216 1119 333 205 1120 319 206 1121 320 218 1122 335 202 1123 316 203 1124 317 203 1125 317 217 1126 334 218 1127 335 232 1128 354 211 1129 328 212 1130 329 212 1131 329 233 1132 355 232 1133 354 230 1134 349 232 1135 354 233 1136 355 233 1137 355 229 1138 348 230 1139 349 186 1140 299 204 1141 318 205 1142 319 205 1143 319 185 1144 298 186 1145 299 184 1146 297 203 1147 317 200 1148 314 200 1149 314 183 1150 296 184 1151 297 182 1152 357 234 1153 356 189 1154 302 189 1155 302 190 1156 303 182 1157 357 212 1158 329 210 1159 326 187 1160 300 187 1161 300 188 1162 301 212 1163 329 194 1164 307 220 1165 337 217 1166 334 217 1167 334 193 1168 306 194 1169 307 192 1170 305 216 1171 333 213 1172 330 213 1173 330 191 1174 304 192 1175 305 198 1176 311 229 1177 348 233 1178 355 233 1179 355 197 1180 310 198 1181 311 183 1182 296 200 1183 314 229 1184 348 229 1185 348 198 1186 311 183 1187 296 195 1188 308 227 1189 344 204 1190 318 204 1191 318 186 1192 299 195 1193 308 178 1194 313 180 1195 351 220 1196 337 220 1197 337 194 1198 307 178 1199 313 213 1200 330 231 1201 352 199 1202 312 199 1203 312 191 1204 304 213 1205 330 217 1206 334 203 1207 317 184 1208 297 184 1209 297 193 1210 306 217 1211 334 205 1212 319 216 1213 333 192 1214 305 192 1215 305 185 1216 298 205 1217 319 197 1218 310 233 1219 355 212 1220 329 212 1221 329 188 1222 301 197 1223 310 196 1224 309 234 1225 356 227 1226 344 221 1227 359 222 1228 358 225 1229 342 225 1230 342 226 1231 343 221 1232 359 128 1233 325 208 1234 322 234 1235 356 234 1236 356 182 1237 357 128 1238 325 208 1239 322 221 1240 338 226 1241 360 226 1242 360 234 1243 356 208 1244 322 234 1245 356 196 1246 309 189 1247 302 196 1248 309 227 1249 344 195 1250 308 223 1251 347 227 1252 344 234 1253 356 234 1254 356 226 1255 360 223 1256 347 236 1257 362 235 1258 361 238 1259 364 238 1260 364 237 1261 363 236 1262 362 240 1263 366 239 1264 365 242 1265 368 242 1266 368 241 1267 367 240 1268 366 238 1269 364 244 1270 370 243 1271 369 243 1272 369 237 1273 363 238 1274 364 241 1275 367 242 1276 368 246 1277 372 246 1278 372 245 1279 371 241 1280 367 249 1281 375 248 1282 374 247 1283 373 247 1284 373 250 1285 376 249 1286 375 251 1287 377 249 1288 375 250 1289 376 250 1290 376 252 1291 378 251 1292 377 250 1293 376 247 1294 373 246 1295 372 246 1296 372 242 1297 368 250 1298 376 252 1299 378 250 1300 376 242 1301 368 242 1302 368 239 1303 365 252 1304 378 253 1305 379 256 1306 382 255 1307 381 255 1308 381 254 1309 380 253 1310 379 255 1311 381 256 1312 382 258 1313 384 258 1314 384 257 1315 383 255 1316 381 254 1317 380 260 1318 386 259 1319 385 259 1320 385 253 1321 379 254 1322 380 262 1323 388 261 1324 387 263 1325 390 263 1326 390 740 1327 389 262 1328 388 264 1329 391 266 1330 395 259 1331 394 264 1332 391 259 1333 394 260 1334 393 264 1335 391 260 1336 393 265 1337 392 266 1338 395 264 1339 391 268 1340 397 268 1341 397 267 1342 396 266 1343 395 267 1344 396 268 1345 397 270 1346 399 270 1347 399 269 1348 398 267 1349 396 269 1350 398 270 1351 399 272 1352 401 272 1353 401 271 1354 400 269 1355 398 272 1356 401 274 1357 403 273 1358 402 273 1359 402 271 1360 400 272 1361 401 274 1362 403 276 1363 405 275 1364 404 275 1365 404 273 1366 402 274 1367 403 278 1368 407 277 1369 406 118 1370 409 118 1371 409 117 1372 408 278 1373 407 279 1374 410 280 1375 411 257 1376 383 257 1377 383 258 1378 384 279 1379 410 281 1380 412 284 1381 415 283 1382 414 283 1383 414 282 1384 413 281 1385 412 284 1386 415 286 1387 417 285 1388 416 285 1389 416 283 1390 414 284 1391 415 287 1392 418 289 1393 422 277 1394 421 287 1395 418 277 1396 421 278 1397 420 287 1398 418 278 1399 420 288 1400 419 289 1401 422 287 1402 418 291 1403 424 291 1404 424 290 1405 423 289 1406 422 290 1407 423 291 1408 424 293 1409 426 293 1410 426 292 1411 425 290 1412 423 292 1413 425 293 1414 426 281 1415 412 281 1416 412 282 1417 413 292 1418 425 294 1419 427 295 1420 428 252 1421 378 252 1422 378 239 1423 365 294 1424 427 295 1425 428 296 1426 429 251 1427 377 251 1428 377 252 1429 378 295 1430 428 298 1431 431 297 1432 430 775 1433 433 775 1434 433 299 1435 432 298 1436 431 300 1437 434 303 1438 437 302 1439 436 302 1440 436 301 1441 435 300 1442 434 304 1443 438 303 1444 437 300 1445 434 300 1446 434 305 1447 439 304 1448 438 306 1449 440 304 1450 438 305 1451 439 305 1452 439 307 1453 441 306 1454 440 308 1455 442 306 1456 440 307 1457 441 307 1458 441 309 1459 443 308 1460 442 310 1461 444 308 1462 442 309 1463 443 309 1464 443 311 1465 445 310 1466 444 313 1467 447 312 1468 446 314 1469 449 314 1470 449 119 1471 448 313 1472 447 119 1473 448 314 1474 449 316 1475 451 316 1476 451 315 1477 450 119 1478 448 317 1479 452 246 1480 372 247 1481 373 247 1482 373 318 1483 453 317 1484 452 248 1485 374 319 1486 454 318 1487 453 318 1488 453 247 1489 373 248 1490 374 320 1491 455 323 1492 458 322 1493 457 322 1494 457 321 1495 456 320 1496 455 324 1497 459 325 1498 460 320 1499 455 320 1500 455 321 1501 456 324 1502 459 326 1503 461 325 1504 460 324 1505 459 324 1506 459 327 1507 462 326 1508 461 328 1509 463 329 1510 464 326 1511 461 326 1512 461 327 1513 462 328 1514 463 323 1515 458 331 1516 466 330 1517 465 330 1518 465 322 1519 457 323 1520 458 262 1521 388 332 1522 467 275 1523 468 275 1524 468 261 1525 387 262 1526 388 261 1527 469 275 1528 404 276 1529 405 276 1530 405 333 1531 471 263 1532 470 261 1533 469 276 1534 405 263 1535 470 276 1536 473 264 1537 472 265 1538 475 265 1539 475 333 1540 474 276 1541 473 282 1542 477 283 1543 476 335 1544 479 335 1545 479 334 1546 478 282 1547 477 279 1548 480 285 1549 416 286 1550 417 286 1551 417 336 1552 482 280 1553 481 279 1554 480 286 1555 417 280 1556 481 288 1557 483 336 1558 486 286 1559 485 286 1560 485 287 1561 484 288 1562 483 303 1563 487 337 1564 490 812 1565 489 812 1566 489 813 1567 488 303 1568 487 301 1569 435 302 1570 436 339 1571 494 339 1572 494 297 1573 493 298 1574 492 339 1575 494 298 1576 492 338 1577 491 301 1578 435 339 1579 494 338 1580 491 294 1581 495 310 1582 444 311 1583 445 294 1584 495 311 1585 445 340 1586 498 294 1587 495 340 1588 498 296 1589 497 294 1590 495 296 1591 497 295 1592 496 301 1593 499 338 1594 502 340 1595 501 340 1596 501 311 1597 500 301 1598 499 578 1599 503 338 1600 506 951 1601 1444 245 1602 371 246 1603 372 317 1604 452 317 1605 452 331 1606 507 245 1607 371 328 1608 463 341 1609 511 316 1610 510 316 1611 510 314 1612 509 312 1613 508 316 1614 510 312 1615 508 329 1616 464 328 1617 463 316 1618 510 329 1619 464 342 1620 512 341 1621 515 328 1622 514 328 1623 514 330 1624 513 342 1625 512 319 1626 516 342 1627 519 330 1628 465 319 1629 516 330 1630 465 331 1631 466 319 1632 516 331 1633 466 317 1634 518 319 1635 516 317 1636 518 318 1637 517 339 1638 521 343 1639 520 775 1640 433 775 1641 433 297 1642 430 339 1643 521 342 1644 527 319 1645 526 248 1646 525 342 1647 527 248 1648 525 251 1649 524 340 1650 522 342 1651 527 251 1652 524 340 1653 522 251 1654 524 296 1655 523 251 1656 524 248 1657 525 249 1658 528 340 1659 522 578 1660 503 342 1661 527 341 1662 529 115 1663 532 315 1664 531 315 1665 531 316 1666 530 341 1667 529 269 1668 534 271 1669 533 345 1670 536 345 1671 536 344 1672 535 269 1673 534 345 1674 536 304 1675 538 306 1676 537 306 1677 537 344 1678 535 345 1679 536 266 1680 540 267 1681 539 243 1682 369 243 1683 369 244 1684 370 266 1685 540 239 1686 365 240 1687 366 310 1688 541 310 1689 541 294 1690 427 239 1691 365 306 1692 537 308 1693 542 346 1694 543 346 1695 543 344 1696 535 306 1697 537 346 1698 543 267 1699 539 269 1700 534 269 1701 534 344 1702 535 346 1703 543 271 1704 533 273 1705 544 337 1706 490 337 1707 490 345 1708 536 271 1709 533 337 1710 490 303 1711 487 304 1712 538 304 1713 538 345 1714 536 337 1715 490 302 1716 545 303 1717 487 813 1718 488 813 1719 488 822 1720 546 302 1721 545 273 1722 544 275 1723 468 332 1724 467 332 1725 467 823 1726 547 273 1727 544 308 1728 542 310 1729 541 240 1730 366 240 1731 366 347 1732 548 308 1733 542 347 1734 548 240 1735 366 241 1736 367 241 1737 367 348 1738 549 347 1739 548 348 1740 549 241 1741 367 245 1742 371 245 1743 371 349 1744 550 348 1745 549 349 1746 550 245 1747 371 331 1748 507 331 1749 507 323 1750 551 349 1751 550 308 1752 542 347 1753 548 350 1754 552 350 1755 552 346 1756 543 308 1757 542 350 1758 552 347 1759 548 348 1760 549 348 1761 549 351 1762 553 350 1763 552 351 1764 553 348 1765 549 349 1766 550 349 1767 550 352 1768 554 351 1769 553 334 1770 478 335 1771 479 323 1772 551 323 1773 551 320 1774 555 334 1775 478 282 1776 477 334 1777 478 353 1778 557 353 1779 557 292 1780 556 282 1781 477 353 1782 557 334 1783 478 320 1784 555 320 1785 555 325 1786 558 353 1787 557 352 1788 554 349 1789 550 323 1790 551 323 1791 551 335 1792 479 352 1793 554 236 1794 362 283 1795 476 285 1796 559 285 1797 559 235 1798 361 236 1799 362 335 1800 479 283 1801 476 236 1802 362 236 1803 362 352 1804 554 335 1805 479 352 1806 554 236 1807 362 237 1808 363 237 1809 363 351 1810 553 352 1811 554 237 1812 363 243 1813 369 350 1814 552 350 1815 552 351 1816 553 237 1817 363 267 1818 539 346 1819 543 350 1820 552 350 1821 552 243 1822 369 267 1823 539 266 1824 540 244 1825 370 253 1826 379 253 1827 379 259 1828 385 266 1829 540 244 1830 370 238 1831 364 256 1832 382 256 1833 382 253 1834 379 244 1835 370 256 1836 382 238 1837 364 235 1838 361 235 1839 361 258 1840 384 256 1841 382 258 1842 384 235 1843 361 285 1844 559 285 1845 559 279 1846 410 258 1847 384 120 1848 561 290 1849 560 355 1850 563 355 1851 563 354 1852 562 120 1853 561 313 1854 447 121 1855 564 329 1856 565 329 1857 565 312 1858 446 313 1859 447 325 1860 558 326 1861 566 355 1862 563 355 1863 563 353 1864 557 325 1865 558 355 1866 563 290 1867 560 292 1868 556 292 1869 556 353 1870 557 355 1871 563 289 1872 567 290 1873 560 120 1874 561 120 1875 561 114 1876 568 289 1877 567 289 1878 567 114 1879 568 118 1880 409 118 1881 409 277 1882 406 289 1883 567 326 1884 566 329 1885 565 121 1886 564 121 1887 564 356 1888 569 326 1889 566 326 1890 566 356 1891 569 354 1892 562 354 1893 562 355 1894 563 326 1895 566 339 1896 521 302 1897 545 822 1898 546 822 1899 546 343 1900 520 339 1901 521 273 1902 544 823 1903 547 812 1904 489 812 1905 489 337 1906 490 273 1907 544 342 1908 527 578 1909 503 341 1910 529 578 1911 503 340 1912 522 338 1913 506 341 1914 529 578 1915 503 115 1916 532 300 1917 570 301 1918 499 311 1919 500 311 1920 500 309 1921 571 300 1922 570 305 1923 572 300 1924 570 309 1925 571 309 1926 571 307 1927 573 305 1928 572 270 1929 575 268 1930 574 274 1931 577 274 1932 577 272 1933 576 270 1934 575 268 1935 574 264 1936 472 276 1937 473 276 1938 473 274 1939 577 268 1940 574 291 1941 578 287 1942 484 286 1943 485 286 1944 485 284 1945 579 291 1946 578 293 1947 580 291 1948 578 284 1949 579 284 1950 579 281 1951 581 293 1952 580 322 1953 582 330 1954 513 328 1955 514 328 1956 514 327 1957 583 322 1958 582 321 1959 584 322 1960 582 327 1961 583 327 1962 583 324 1963 585 321 1964 584 358 1965 587 357 1966 586 945 1967 589 945 1968 589 359 1969 588 358 1970 587 361 1971 590 358 1972 587 359 1973 588 359 1974 588 946 1975 591 361 1976 590 363 1977 592 366 1978 595 365 1979 594 365 1980 594 364 1981 593 363 1982 592 370 1983 599 369 1984 598 368 1985 597 368 1986 597 367 1987 596 370 1988 599 371 1989 600 374 1990 603 373 1991 602 373 1992 602 372 1993 601 371 1994 600 375 1995 604 378 1996 607 377 1997 606 377 1998 606 376 1999 605 375 2000 604 366 2001 595 363 2002 592 378 2003 607 378 2004 607 375 2005 604 366 2006 595 379 2007 608 380 2008 609 374 2009 603 374 2010 603 371 2011 600 379 2012 608 373 2013 602 364 2014 593 365 2015 594 365 2016 594 372 2017 601 373 2018 602 376 2019 605 377 2020 606 368 2021 597 368 2022 597 369 2023 598 376 2024 605 383 2025 612 382 2026 611 381 2027 610 381 2028 610 384 2029 613 383 2030 612 388 2031 617 387 2032 616 386 2033 615 386 2034 615 385 2035 614 388 2036 617 391 2037 620 390 2038 619 389 2039 618 389 2040 618 392 2041 621 391 2042 620 395 2043 624 394 2044 623 393 2045 622 393 2046 622 396 2047 625 395 2048 624 399 2049 628 398 2050 627 397 2051 626 397 2052 626 400 2053 629 399 2054 628 403 2055 632 402 2056 631 401 2057 630 401 2058 630 404 2059 633 403 2060 632 390 2061 619 406 2062 635 405 2063 634 405 2064 634 389 2065 618 390 2066 619 410 2067 639 409 2068 638 408 2069 637 408 2070 637 407 2071 636 410 2072 639 408 2073 642 412 2074 641 411 2075 640 411 2076 640 407 2077 643 408 2078 642 382 2079 611 414 2080 645 413 2081 644 413 2082 644 381 2083 610 382 2084 611 412 2085 641 388 2086 617 385 2087 614 385 2088 614 411 2089 640 412 2090 641 415 2091 646 403 2092 632 404 2093 633 404 2094 633 416 2095 647 415 2096 646 398 2097 627 418 2098 649 417 2099 648 417 2100 648 397 2101 626 398 2102 627 387 2103 616 399 2104 628 400 2105 629 400 2106 629 386 2107 615 387 2108 616 402 2109 631 383 2110 612 384 2111 613 384 2112 613 401 2113 630 402 2114 631 419 2115 650 395 2116 624 396 2117 625 396 2118 625 420 2119 651 419 2120 650 414 2121 645 419 2122 650 420 2123 651 420 2124 651 413 2125 644 414 2126 645 366 2127 595 385 2128 614 386 2129 615 386 2130 615 365 2131 594 366 2132 595 364 2133 593 384 2134 613 381 2135 610 381 2136 610 363 2137 592 364 2138 593 422 2139 653 421 2140 652 369 2141 598 369 2142 598 370 2143 599 422 2144 653 396 2145 625 393 2146 622 367 2147 596 367 2148 596 368 2149 597 396 2150 625 374 2151 603 404 2152 633 401 2153 630 401 2154 630 373 2155 602 374 2156 603 372 2157 601 400 2158 629 397 2159 626 397 2160 626 371 2161 600 372 2162 601 378 2163 607 413 2164 644 420 2165 651 420 2166 651 377 2167 606 378 2168 607 363 2169 592 381 2170 610 413 2171 644 413 2172 644 378 2173 607 363 2174 592 375 2175 604 411 2176 640 385 2177 614 385 2178 614 366 2179 595 375 2180 604 380 2181 609 416 2182 647 404 2183 633 404 2184 633 374 2185 603 380 2186 609 397 2187 626 417 2188 648 379 2189 608 379 2190 608 371 2191 600 397 2192 626 401 2193 630 384 2194 613 364 2195 593 364 2196 593 373 2197 602 401 2198 630 386 2199 615 400 2200 629 372 2201 601 372 2202 601 365 2203 594 386 2204 615 377 2205 606 420 2206 651 396 2207 625 396 2208 625 368 2209 597 377 2210 606 376 2211 605 421 2212 652 411 2213 640 405 2214 655 406 2215 654 409 2216 638 409 2217 638 410 2218 639 405 2219 655 392 2220 621 389 2221 618 421 2222 652 421 2223 652 422 2224 653 392 2225 621 389 2226 618 405 2227 634 410 2228 656 410 2229 656 421 2230 652 389 2231 618 421 2232 652 376 2233 605 369 2234 598 376 2235 605 411 2236 640 375 2237 604 407 2238 643 411 2239 640 421 2240 652 421 2241 652 410 2242 656 407 2243 643 423 2244 657 426 2245 660 425 2246 659 425 2247 659 424 2248 658 423 2249 657 370 2250 662 367 2251 661 428 2252 664 428 2253 664 427 2254 663 370 2255 662 429 2256 665 432 2257 668 431 2258 667 431 2259 667 430 2260 666 429 2261 665 433 2262 669 436 2263 672 435 2264 671 435 2265 671 434 2266 670 433 2267 669 424 2268 658 433 2269 669 434 2270 670 434 2271 670 423 2272 657 424 2273 658 379 2274 673 429 2275 665 430 2276 666 430 2277 666 380 2278 674 379 2279 673 431 2280 667 432 2281 668 425 2282 659 425 2283 659 426 2284 660 431 2285 667 436 2286 672 427 2287 663 428 2288 664 428 2289 664 435 2290 671 436 2291 672 439 2292 677 438 2293 676 437 2294 675 437 2295 675 440 2296 678 439 2297 677 442 2298 680 441 2299 679 444 2300 682 444 2301 682 443 2302 681 442 2303 680 391 2304 685 392 2305 684 445 2306 683 445 2307 683 446 2308 686 391 2309 685 448 2310 689 447 2311 688 393 2312 687 393 2313 687 394 2314 690 448 2315 689 451 2316 693 450 2317 692 449 2318 691 449 2319 691 452 2320 694 451 2321 693 455 2322 697 454 2323 696 453 2324 695 453 2325 695 456 2326 698 455 2327 697 446 2328 686 445 2329 683 457 2330 699 457 2331 699 362 2332 700 446 2333 686 459 2334 702 458 2335 701 360 2336 704 360 2337 704 460 2338 703 459 2339 702 360 2340 707 458 2341 706 461 2342 705 461 2343 705 462 2344 708 360 2345 707 440 2346 678 437 2347 675 463 2348 709 463 2349 709 464 2350 710 440 2351 678 462 2352 708 461 2353 705 441 2354 679 441 2355 679 442 2356 680 462 2357 708 415 2358 712 416 2359 711 454 2360 696 454 2361 696 455 2362 697 415 2363 712 452 2364 694 449 2365 691 417 2366 713 417 2367 713 418 2368 714 452 2369 694 443 2370 681 444 2371 682 450 2372 692 450 2373 692 451 2374 693 443 2375 681 456 2376 698 453 2377 695 438 2378 676 438 2379 676 439 2380 677 456 2381 698 466 2382 716 465 2383 715 447 2384 688 447 2385 688 448 2386 689 466 2387 716 464 2388 710 463 2389 709 465 2390 715 465 2391 715 466 2392 716 464 2393 710 424 2394 658 425 2395 659 444 2396 682 444 2397 682 441 2398 679 424 2399 658 426 2400 660 423 2401 657 437 2402 675 437 2403 675 438 2404 676 426 2405 660 422 2406 717 370 2407 662 427 2408 663 427 2409 663 467 2410 718 422 2411 717 447 2412 688 428 2413 664 367 2414 661 367 2415 661 393 2416 687 447 2417 688 430 2418 666 431 2419 667 453 2420 695 453 2421 695 454 2422 696 430 2423 666 432 2424 668 429 2425 665 449 2426 691 449 2427 691 450 2428 692 432 2429 668 434 2430 670 435 2431 671 465 2432 715 465 2433 715 463 2434 709 434 2435 670 423 2436 657 434 2437 670 463 2438 709 463 2439 709 437 2440 675 423 2441 657 433 2442 669 424 2443 658 441 2444 679 441 2445 679 461 2446 705 433 2447 669 380 2448 674 430 2449 666 454 2450 696 454 2451 696 416 2452 711 380 2453 674 449 2454 691 429 2455 665 379 2456 673 379 2457 673 417 2458 713 449 2459 691 453 2460 695 431 2461 667 426 2462 660 426 2463 660 438 2464 676 453 2465 695 444 2466 682 425 2467 659 432 2468 668 432 2469 668 450 2470 692 444 2471 682 435 2472 671 428 2473 664 447 2474 688 447 2475 688 465 2476 715 435 2477 671 436 2478 672 461 2479 705 467 2480 718 457 2481 719 459 2482 702 460 2483 703 460 2484 703 362 2485 720 457 2486 719 392 2487 684 422 2488 717 467 2489 718 467 2490 718 445 2491 683 392 2492 684 445 2493 683 467 2494 718 459 2495 721 459 2496 721 457 2497 699 445 2498 683 467 2499 718 427 2500 663 436 2501 672 436 2502 672 433 2503 669 461 2504 705 458 2505 706 459 2506 721 467 2507 718 467 2508 718 461 2509 705 458 2510 706 469 2511 723 468 2512 722 471 2513 725 471 2514 725 470 2515 724 469 2516 723 473 2517 727 472 2518 726 475 2519 729 475 2520 729 474 2521 728 473 2522 727 471 2523 725 477 2524 731 476 2525 730 476 2526 730 470 2527 724 471 2528 725 474 2529 728 475 2530 729 479 2531 733 479 2532 733 478 2533 732 474 2534 728 482 2535 736 481 2536 735 480 2537 734 480 2538 734 483 2539 737 482 2540 736 484 2541 738 482 2542 736 483 2543 737 483 2544 737 485 2545 739 484 2546 738 483 2547 737 480 2548 734 479 2549 733 479 2550 733 475 2551 729 483 2552 737 485 2553 739 483 2554 737 475 2555 729 475 2556 729 472 2557 726 485 2558 739 486 2559 740 489 2560 743 488 2561 742 488 2562 742 487 2563 741 486 2564 740 488 2565 742 489 2566 743 491 2567 745 491 2568 745 490 2569 744 488 2570 742 487 2571 741 493 2572 747 492 2573 746 492 2574 746 486 2575 740 487 2576 741 495 2577 749 494 2578 748 497 2579 751 497 2580 751 496 2581 750 495 2582 749 498 2583 752 500 2584 756 492 2585 755 498 2586 752 492 2587 755 493 2588 754 498 2589 752 493 2590 754 499 2591 753 500 2592 756 498 2593 752 502 2594 758 502 2595 758 501 2596 757 500 2597 756 501 2598 757 502 2599 758 504 2600 760 504 2601 760 503 2602 759 501 2603 757 503 2604 759 504 2605 760 506 2606 762 506 2607 762 505 2608 761 503 2609 759 506 2610 762 508 2611 764 507 2612 763 507 2613 763 505 2614 761 506 2615 762 508 2616 764 510 2617 766 509 2618 765 509 2619 765 507 2620 763 508 2621 764 512 2622 768 511 2623 767 514 2624 770 514 2625 770 513 2626 769 512 2627 768 515 2628 771 516 2629 772 490 2630 744 490 2631 744 491 2632 745 515 2633 771 517 2634 773 520 2635 776 519 2636 775 519 2637 775 518 2638 774 517 2639 773 520 2640 776 522 2641 778 521 2642 777 521 2643 777 519 2644 775 520 2645 776 523 2646 779 525 2647 783 511 2648 782 523 2649 779 511 2650 782 512 2651 781 523 2652 779 512 2653 781 524 2654 780 525 2655 783 523 2656 779 527 2657 785 527 2658 785 526 2659 784 525 2660 783 526 2661 784 527 2662 785 529 2663 787 529 2664 787 528 2665 786 526 2666 784 528 2667 786 529 2668 787 517 2669 773 517 2670 773 518 2671 774 528 2672 786 530 2673 788 531 2674 789 485 2675 739 485 2676 739 472 2677 726 530 2678 788 531 2679 789 532 2680 790 484 2681 738 484 2682 738 485 2683 739 531 2684 789 534 2685 792 533 2686 791 122 2687 794 122 2688 794 116 2689 793 534 2690 792 535 2691 795 538 2692 798 537 2693 797 537 2694 797 536 2695 796 535 2696 795 539 2697 799 538 2698 798 535 2699 795 535 2700 795 540 2701 800 539 2702 799 541 2703 801 539 2704 799 540 2705 800 540 2706 800 542 2707 802 541 2708 801 543 2709 803 541 2710 801 542 2711 802 542 2712 802 544 2713 804 543 2714 803 545 2715 805 543 2716 803 544 2717 804 544 2718 804 546 2719 806 545 2720 805 548 2721 808 547 2722 807 550 2723 810 550 2724 810 549 2725 809 548 2726 808 549 2727 809 550 2728 810 552 2729 812 552 2730 812 551 2731 811 549 2732 809 553 2733 813 479 2734 733 480 2735 734 480 2736 734 554 2737 814 553 2738 813 481 2739 735 555 2740 815 554 2741 814 554 2742 814 480 2743 734 481 2744 735 556 2745 816 559 2746 819 558 2747 818 558 2748 818 557 2749 817 556 2750 816 560 2751 820 561 2752 821 556 2753 816 556 2754 816 557 2755 817 560 2756 820 562 2757 822 561 2758 821 560 2759 820 560 2760 820 563 2761 823 562 2762 822 564 2763 824 565 2764 825 562 2765 822 562 2766 822 563 2767 823 564 2768 824 559 2769 819 567 2770 827 566 2771 826 566 2772 826 558 2773 818 559 2774 819 495 2775 749 568 2776 828 509 2777 829 509 2778 829 494 2779 748 495 2780 749 494 2781 830 509 2782 765 510 2783 766 510 2784 766 569 2785 832 497 2786 831 494 2787 830 510 2788 766 497 2789 831 510 2790 834 498 2791 833 499 2792 836 499 2793 836 569 2794 835 510 2795 834 518 2796 838 519 2797 837 571 2798 840 571 2799 840 570 2800 839 518 2801 838 515 2802 841 521 2803 777 522 2804 778 522 2805 778 572 2806 843 516 2807 842 515 2808 841 522 2809 778 516 2810 842 524 2811 844 572 2812 847 522 2813 846 522 2814 846 523 2815 845 524 2816 844 538 2817 848 574 2818 851 573 2819 850 573 2820 850 123 2821 849 538 2822 848 536 2823 796 537 2824 797 576 2825 855 576 2826 855 533 2827 854 534 2828 853 576 2829 855 534 2830 853 575 2831 852 536 2832 796 576 2833 855 575 2834 852 530 2835 856 545 2836 805 546 2837 806 530 2838 856 546 2839 806 577 2840 859 530 2841 856 577 2842 859 532 2843 858 530 2844 856 532 2845 858 531 2846 857 536 2847 860 575 2848 863 577 2849 862 577 2850 862 546 2851 861 536 2852 860 116 2853 865 952 2854 1446 575 2855 867 575 2856 867 534 2857 866 116 2858 865 478 2859 732 479 2860 733 553 2861 813 553 2862 813 567 2863 868 478 2864 732 564 2865 824 579 2866 872 552 2867 871 552 2868 871 550 2869 870 547 2870 869 552 2871 871 547 2872 869 565 2873 825 564 2874 824 552 2875 871 565 2876 825 580 2877 873 579 2878 876 564 2879 875 564 2880 875 566 2881 874 580 2882 873 555 2883 877 580 2884 880 566 2885 826 555 2886 877 566 2887 826 567 2888 827 555 2889 877 567 2890 827 553 2891 879 555 2892 877 553 2893 879 554 2894 878 576 2895 882 581 2896 881 122 2897 794 122 2898 794 533 2899 791 576 2900 882 580 2901 888 555 2902 887 481 2903 886 580 2904 888 481 2905 886 484 2906 885 577 2907 883 580 2908 888 484 2909 885 577 2910 883 484 2911 885 532 2912 884 484 2913 885 481 2914 886 482 2915 889 577 2916 883 578 2917 864 580 2918 888 579 2919 890 582 2920 893 551 2921 892 551 2922 892 552 2923 891 579 2924 890 503 2925 895 505 2926 894 584 2927 897 584 2928 897 583 2929 896 503 2930 895 584 2931 897 539 2932 899 541 2933 898 541 2934 898 583 2935 896 584 2936 897 500 2937 901 501 2938 900 476 2939 730 476 2940 730 477 2941 731 500 2942 901 472 2943 726 473 2944 727 545 2945 902 545 2946 902 530 2947 788 472 2948 726 541 2949 898 543 2950 903 585 2951 904 585 2952 904 583 2953 896 541 2954 898 585 2955 904 501 2956 900 503 2957 895 503 2958 895 583 2959 896 585 2960 904 505 2961 894 507 2962 905 574 2963 851 574 2964 851 584 2965 897 505 2966 894 574 2967 851 538 2968 848 539 2969 899 539 2970 899 584 2971 897 574 2972 851 537 2973 906 538 2974 848 123 2975 849 123 2976 849 586 2977 907 537 2978 906 507 2979 905 509 2980 829 568 2981 828 568 2982 828 587 2983 908 507 2984 905 543 2985 903 545 2986 902 473 2987 727 473 2988 727 588 2989 909 543 2990 903 588 2991 909 473 2992 727 474 2993 728 474 2994 728 589 2995 910 588 2996 909 589 2997 910 474 2998 728 478 2999 732 478 3000 732 590 3001 911 589 3002 910 590 3003 911 478 3004 732 567 3005 868 567 3006 868 559 3007 912 590 3008 911 543 3009 903 588 3010 909 591 3011 913 591 3012 913 585 3013 904 543 3014 903 591 3015 913 588 3016 909 589 3017 910 589 3018 910 592 3019 914 591 3020 913 592 3021 914 589 3022 910 590 3023 911 590 3024 911 593 3025 915 592 3026 914 570 3027 839 571 3028 840 559 3029 912 559 3030 912 556 3031 916 570 3032 839 518 3033 838 570 3034 839 594 3035 918 594 3036 918 528 3037 917 518 3038 838 594 3039 918 570 3040 839 556 3041 916 556 3042 916 561 3043 919 594 3044 918 593 3045 915 590 3046 911 559 3047 912 559 3048 912 571 3049 840 593 3050 915 469 3051 723 519 3052 837 521 3053 920 521 3054 920 468 3055 722 469 3056 723 571 3057 840 519 3058 837 469 3059 723 469 3060 723 593 3061 915 571 3062 840 593 3063 915 469 3064 723 470 3065 724 470 3066 724 592 3067 914 593 3068 915 470 3069 724 476 3070 730 591 3071 913 591 3072 913 592 3073 914 470 3074 724 501 3075 900 585 3076 904 591 3077 913 591 3078 913 476 3079 730 501 3080 900 500 3081 901 477 3082 731 486 3083 740 486 3084 740 492 3085 746 500 3086 901 477 3087 731 471 3088 725 489 3089 743 489 3090 743 486 3091 740 477 3092 731 489 3093 743 471 3094 725 468 3095 722 468 3096 722 491 3097 745 489 3098 743 491 3099 745 468 3100 722 521 3101 920 521 3102 920 515 3103 771 491 3104 745 595 3105 922 526 3106 921 597 3107 924 597 3108 924 596 3109 923 595 3110 922 548 3111 808 598 3112 925 565 3113 926 565 3114 926 547 3115 807 548 3116 808 561 3117 919 562 3118 927 597 3119 924 597 3120 924 594 3121 918 561 3122 919 597 3123 924 526 3124 921 528 3125 917 528 3126 917 594 3127 918 597 3128 924 525 3129 928 526 3130 921 595 3131 922 595 3132 922 599 3133 929 525 3134 928 525 3135 928 599 3136 929 514 3137 770 514 3138 770 511 3139 767 525 3140 928 562 3141 927 565 3142 926 598 3143 925 598 3144 925 600 3145 930 562 3146 927 562 3147 927 600 3148 930 596 3149 923 596 3150 923 597 3151 924 562 3152 927 576 3153 882 537 3154 906 586 3155 907 586 3156 907 581 3157 881 576 3158 882 507 3159 905 587 3160 908 573 3161 850 573 3162 850 574 3163 851 507 3164 905 580 3165 888 578 3166 864 579 3167 890 578 3168 864 577 3169 883 575 3170 867 579 3171 890 578 3172 864 582 3173 893 535 3174 931 536 3175 860 546 3176 861 546 3177 861 544 3178 932 535 3179 931 540 3180 933 535 3181 931 544 3182 932 544 3183 932 542 3184 934 540 3185 933 504 3186 936 502 3187 935 508 3188 938 508 3189 938 506 3190 937 504 3191 936 502 3192 935 498 3193 833 510 3194 834 510 3195 834 508 3196 938 502 3197 935 527 3198 939 523 3199 845 522 3200 846 522 3201 846 520 3202 940 527 3203 939 529 3204 941 527 3205 939 520 3206 940 520 3207 940 517 3208 942 529 3209 941 558 3210 943 566 3211 874 564 3212 875 564 3213 875 563 3214 944 558 3215 943 557 3216 945 558 3217 943 563 3218 944 563 3219 944 560 3220 946 557 3221 945 602 3222 948 601 3223 947 947 3224 950 947 3225 950 603 3226 949 602 3227 948 605 3228 951 602 3229 948 603 3230 949 603 3231 949 948 3232 952 605 3233 951 607 3234 953 610 3235 956 609 3236 955 609 3237 955 608 3238 954 607 3239 953 614 3240 960 613 3241 959 612 3242 958 612 3243 958 611 3244 957 614 3245 960 615 3246 961 618 3247 964 617 3248 963 617 3249 963 616 3250 962 615 3251 961 619 3252 965 622 3253 968 621 3254 967 621 3255 967 620 3256 966 619 3257 965 610 3258 956 607 3259 953 622 3260 968 622 3261 968 619 3262 965 610 3263 956 623 3264 969 624 3265 970 618 3266 964 618 3267 964 615 3268 961 623 3269 969 617 3270 963 608 3271 954 609 3272 955 609 3273 955 616 3274 962 617 3275 963 620 3276 966 621 3277 967 612 3278 958 612 3279 958 613 3280 959 620 3281 966 627 3282 973 626 3283 972 625 3284 971 625 3285 971 628 3286 974 627 3287 973 632 3288 978 631 3289 977 630 3290 976 630 3291 976 629 3292 975 632 3293 978 635 3294 981 634 3295 980 633 3296 979 633 3297 979 636 3298 982 635 3299 981 639 3300 985 638 3301 984 637 3302 983 637 3303 983 640 3304 986 639 3305 985 643 3306 989 642 3307 988 641 3308 987 641 3309 987 644 3310 990 643 3311 989 647 3312 993 646 3313 992 645 3314 991 645 3315 991 648 3316 994 647 3317 993 634 3318 980 650 3319 996 649 3320 995 649 3321 995 633 3322 979 634 3323 980 654 3324 1000 653 3325 999 652 3326 998 652 3327 998 651 3328 997 654 3329 1000 652 3330 1003 656 3331 1002 655 3332 1001 655 3333 1001 651 3334 1004 652 3335 1003 626 3336 972 658 3337 1006 657 3338 1005 657 3339 1005 625 3340 971 626 3341 972 656 3342 1002 632 3343 978 629 3344 975 629 3345 975 655 3346 1001 656 3347 1002 659 3348 1007 647 3349 993 648 3350 994 648 3351 994 660 3352 1008 659 3353 1007 642 3354 988 662 3355 1010 661 3356 1009 661 3357 1009 641 3358 987 642 3359 988 631 3360 977 643 3361 989 644 3362 990 644 3363 990 630 3364 976 631 3365 977 646 3366 992 627 3367 973 628 3368 974 628 3369 974 645 3370 991 646 3371 992 663 3372 1011 639 3373 985 640 3374 986 640 3375 986 664 3376 1012 663 3377 1011 658 3378 1006 663 3379 1011 664 3380 1012 664 3381 1012 657 3382 1005 658 3383 1006 610 3384 956 629 3385 975 630 3386 976 630 3387 976 609 3388 955 610 3389 956 608 3390 954 628 3391 974 625 3392 971 625 3393 971 607 3394 953 608 3395 954 666 3396 1014 665 3397 1013 613 3398 959 613 3399 959 614 3400 960 666 3401 1014 640 3402 986 637 3403 983 611 3404 957 611 3405 957 612 3406 958 640 3407 986 618 3408 964 648 3409 994 645 3410 991 645 3411 991 617 3412 963 618 3413 964 616 3414 962 644 3415 990 641 3416 987 641 3417 987 615 3418 961 616 3419 962 622 3420 968 657 3421 1005 664 3422 1012 664 3423 1012 621 3424 967 622 3425 968 607 3426 953 625 3427 971 657 3428 1005 657 3429 1005 622 3430 968 607 3431 953 619 3432 965 655 3433 1001 629 3434 975 629 3435 975 610 3436 956 619 3437 965 624 3438 970 660 3439 1008 648 3440 994 648 3441 994 618 3442 964 624 3443 970 641 3444 987 661 3445 1009 623 3446 969 623 3447 969 615 3448 961 641 3449 987 645 3450 991 628 3451 974 608 3452 954 608 3453 954 617 3454 963 645 3455 991 630 3456 976 644 3457 990 616 3458 962 616 3459 962 609 3460 955 630 3461 976 621 3462 967 664 3463 1012 640 3464 986 640 3465 986 612 3466 958 621 3467 967 620 3468 966 665 3469 1013 655 3470 1001 649 3471 1016 650 3472 1015 653 3473 999 653 3474 999 654 3475 1000 649 3476 1016 636 3477 982 633 3478 979 665 3479 1013 665 3480 1013 666 3481 1014 636 3482 982 633 3483 979 649 3484 995 654 3485 1017 654 3486 1017 665 3487 1013 633 3488 979 665 3489 1013 620 3490 966 613 3491 959 620 3492 966 655 3493 1001 619 3494 965 651 3495 1004 655 3496 1001 665 3497 1013 665 3498 1013 654 3499 1017 651 3500 1004 667 3501 1018 670 3502 1021 669 3503 1020 669 3504 1020 668 3505 1019 667 3506 1018 614 3507 1023 611 3508 1022 672 3509 1025 672 3510 1025 671 3511 1024 614 3512 1023 673 3513 1026 676 3514 1029 675 3515 1028 675 3516 1028 674 3517 1027 673 3518 1026 677 3519 1030 680 3520 1033 679 3521 1032 679 3522 1032 678 3523 1031 677 3524 1030 668 3525 1019 677 3526 1030 678 3527 1031 678 3528 1031 667 3529 1018 668 3530 1019 623 3531 1034 673 3532 1026 674 3533 1027 674 3534 1027 624 3535 1035 623 3536 1034 675 3537 1028 676 3538 1029 669 3539 1020 669 3540 1020 670 3541 1021 675 3542 1028 680 3543 1033 671 3544 1024 672 3545 1025 672 3546 1025 679 3547 1032 680 3548 1033 683 3549 1038 682 3550 1037 681 3551 1036 681 3552 1036 684 3553 1039 683 3554 1038 686 3555 1041 685 3556 1040 688 3557 1043 688 3558 1043 687 3559 1042 686 3560 1041 635 3561 1046 636 3562 1045 689 3563 1044 689 3564 1044 690 3565 1047 635 3566 1046 692 3567 1050 691 3568 1049 637 3569 1048 637 3570 1048 638 3571 1051 692 3572 1050 695 3573 1054 694 3574 1053 693 3575 1052 693 3576 1052 696 3577 1055 695 3578 1054 699 3579 1058 698 3580 1057 697 3581 1056 697 3582 1056 700 3583 1059 699 3584 1058 690 3585 1047 689 3586 1044 701 3587 1060 701 3588 1060 606 3589 1061 690 3590 1047 703 3591 1063 702 3592 1062 604 3593 1065 604 3594 1065 704 3595 1064 703 3596 1063 604 3597 1068 702 3598 1067 705 3599 1066 705 3600 1066 706 3601 1069 604 3602 1068 684 3603 1039 681 3604 1036 707 3605 1070 707 3606 1070 708 3607 1071 684 3608 1039 706 3609 1069 705 3610 1066 685 3611 1040 685 3612 1040 686 3613 1041 706 3614 1069 659 3615 1073 660 3616 1072 698 3617 1057 698 3618 1057 699 3619 1058 659 3620 1073 696 3621 1055 693 3622 1052 661 3623 1074 661 3624 1074 662 3625 1075 696 3626 1055 687 3627 1042 688 3628 1043 694 3629 1053 694 3630 1053 695 3631 1054 687 3632 1042 700 3633 1059 697 3634 1056 682 3635 1037 682 3636 1037 683 3637 1038 700 3638 1059 710 3639 1077 709 3640 1076 691 3641 1049 691 3642 1049 692 3643 1050 710 3644 1077 708 3645 1071 707 3646 1070 709 3647 1076 709 3648 1076 710 3649 1077 708 3650 1071 668 3651 1019 669 3652 1020 688 3653 1043 688 3654 1043 685 3655 1040 668 3656 1019 670 3657 1021 667 3658 1018 681 3659 1036 681 3660 1036 682 3661 1037 670 3662 1021 666 3663 1078 614 3664 1023 671 3665 1024 671 3666 1024 711 3667 1079 666 3668 1078 691 3669 1049 672 3670 1025 611 3671 1022 611 3672 1022 637 3673 1048 691 3674 1049 674 3675 1027 675 3676 1028 697 3677 1056 697 3678 1056 698 3679 1057 674 3680 1027 676 3681 1029 673 3682 1026 693 3683 1052 693 3684 1052 694 3685 1053 676 3686 1029 678 3687 1031 679 3688 1032 709 3689 1076 709 3690 1076 707 3691 1070 678 3692 1031 667 3693 1018 678 3694 1031 707 3695 1070 707 3696 1070 681 3697 1036 667 3698 1018 677 3699 1030 668 3700 1019 685 3701 1040 685 3702 1040 705 3703 1066 677 3704 1030 624 3705 1035 674 3706 1027 698 3707 1057 698 3708 1057 660 3709 1072 624 3710 1035 693 3711 1052 673 3712 1026 623 3713 1034 623 3714 1034 661 3715 1074 693 3716 1052 697 3717 1056 675 3718 1028 670 3719 1021 670 3720 1021 682 3721 1037 697 3722 1056 688 3723 1043 669 3724 1020 676 3725 1029 676 3726 1029 694 3727 1053 688 3728 1043 679 3729 1032 672 3730 1025 691 3731 1049 691 3732 1049 709 3733 1076 679 3734 1032 680 3735 1033 705 3736 1066 711 3737 1079 701 3738 1080 703 3739 1063 704 3740 1064 704 3741 1064 606 3742 1081 701 3743 1080 636 3744 1045 666 3745 1078 711 3746 1079 711 3747 1079 689 3748 1044 636 3749 1045 689 3750 1044 711 3751 1079 703 3752 1082 703 3753 1082 701 3754 1060 689 3755 1044 711 3756 1079 671 3757 1024 680 3758 1033 680 3759 1033 677 3760 1030 705 3761 1066 702 3762 1067 703 3763 1082 711 3764 1079 711 3765 1079 705 3766 1066 702 3767 1067 715 3768 1086 714 3769 1085 713 3770 1084 713 3771 1084 712 3772 1083 715 3773 1086 719 3774 1090 718 3775 1089 717 3776 1088 717 3777 1088 716 3778 1087 719 3779 1090 713 3780 1084 714 3781 1085 721 3782 1092 721 3783 1092 720 3784 1091 713 3785 1084 718 3786 1089 723 3787 1094 722 3788 1093 722 3789 1093 717 3790 1088 718 3791 1089 726 3792 1097 725 3793 1096 724 3794 1095 724 3795 1095 727 3796 1098 726 3797 1097 729 3798 1100 728 3799 1099 725 3800 1096 725 3801 1096 726 3802 1097 729 3803 1100 725 3804 1096 717 3805 1088 722 3806 1093 722 3807 1093 724 3808 1095 725 3809 1096 728 3810 1099 716 3811 1087 717 3812 1088 717 3813 1088 725 3814 1096 728 3815 1099 730 3816 1101 733 3817 1104 732 3818 1103 732 3819 1103 731 3820 1102 730 3821 1101 732 3822 1103 735 3823 1106 734 3824 1105 734 3825 1105 731 3826 1102 732 3827 1103 733 3828 1104 730 3829 1101 737 3830 1108 737 3831 1108 736 3832 1107 733 3833 1104 262 3834 1112 740 3835 1111 739 3836 1110 739 3837 1110 738 3838 1109 262 3839 1112 741 3840 1113 743 3841 1117 736 3842 1116 741 3843 1113 736 3844 1116 737 3845 1115 741 3846 1113 737 3847 1115 742 3848 1114 742 3849 1114 745 3850 1119 744 3851 1118 744 3852 1118 741 3853 1113 742 3854 1114 745 3855 1119 747 3856 1121 746 3857 1120 746 3858 1120 744 3859 1118 745 3860 1119 747 3861 1121 749 3862 1123 748 3863 1122 748 3864 1122 746 3865 1120 747 3866 1121 748 3867 1122 749 3868 1123 751 3869 1125 751 3870 1125 750 3871 1124 748 3872 1122 750 3873 1124 751 3874 1125 753 3875 1127 753 3876 1127 752 3877 1126 750 3878 1124 755 3879 1131 513 3880 1130 514 3881 1129 514 3882 1129 754 3883 1128 755 3884 1131 756 3885 1132 734 3886 1105 735 3887 1106 735 3888 1106 757 3889 1133 756 3890 1132 758 3891 1134 761 3892 1137 760 3893 1136 760 3894 1136 759 3895 1135 758 3896 1134 759 3897 1135 760 3898 1136 763 3899 1139 763 3900 1139 762 3901 1138 759 3902 1135 764 3903 1140 766 3904 1144 755 3905 1143 764 3906 1140 755 3907 1143 754 3908 1142 764 3909 1140 754 3910 1142 765 3911 1141 765 3912 1141 768 3913 1146 767 3914 1145 767 3915 1145 764 3916 1140 765 3917 1141 768 3918 1146 770 3919 1148 769 3920 1147 769 3921 1147 767 3922 1145 768 3923 1146 770 3924 1148 761 3925 1137 758 3926 1134 758 3927 1134 769 3928 1147 770 3929 1148 771 3930 1149 716 3931 1087 728 3932 1099 728 3933 1099 772 3934 1150 771 3935 1149 772 3936 1150 728 3937 1099 729 3938 1100 729 3939 1100 773 3940 1151 772 3941 1150 776 3942 1155 299 3943 1154 775 3944 1153 775 3945 1153 774 3946 1152 776 3947 1155 777 3948 1156 780 3949 1159 779 3950 1158 779 3951 1158 778 3952 1157 777 3953 1156 781 3954 1160 782 3955 1161 777 3956 1156 777 3957 1156 778 3958 1157 781 3959 1160 783 3960 1162 784 3961 1163 782 3962 1161 782 3963 1161 781 3964 1160 783 3965 1162 785 3966 1164 786 3967 1165 784 3968 1163 784 3969 1163 783 3970 1162 785 3971 1164 787 3972 1166 788 3973 1167 786 3974 1165 786 3975 1165 785 3976 1164 787 3977 1166 548 3978 1171 549 3979 1170 790 3980 1169 790 3981 1169 789 3982 1168 548 3983 1171 549 3984 1170 551 3985 1173 791 3986 1172 791 3987 1172 790 3988 1169 549 3989 1170 792 3990 1174 793 3991 1175 724 3992 1095 724 3993 1095 722 3994 1093 792 3995 1174 727 3996 1098 724 3997 1095 793 3998 1175 793 3999 1175 794 4000 1176 727 4001 1098 795 4002 1177 798 4003 1180 797 4004 1179 797 4005 1179 796 4006 1178 795 4007 1177 799 4008 1181 798 4009 1180 795 4010 1177 795 4011 1177 800 4012 1182 799 4013 1181 801 4014 1183 802 4015 1184 799 4016 1181 799 4017 1181 800 4018 1182 801 4019 1183 803 4020 1185 802 4021 1184 801 4022 1183 801 4023 1183 804 4024 1186 803 4025 1185 796 4026 1178 797 4027 1179 806 4028 1188 806 4029 1188 805 4030 1187 796 4031 1178 262 4032 1112 738 4033 1109 753 4034 1190 753 4035 1190 332 4036 1189 262 4037 1112 739 4038 1193 807 4039 1192 752 4040 1126 738 4041 1191 739 4042 1193 752 4043 1126 738 4044 1191 752 4045 1126 753 4046 1127 752 4047 1197 807 4048 1196 743 4049 1195 743 4050 1195 741 4051 1194 752 4052 1197 761 4053 1201 809 4054 1200 808 4055 1199 808 4056 1199 760 4057 1198 761 4058 1201 757 4059 1204 810 4060 1203 762 4061 1138 756 4062 1202 757 4063 1204 762 4064 1138 756 4065 1202 762 4066 1138 763 4067 1139 766 4068 1205 764 4069 1208 762 4070 1207 762 4071 1207 810 4072 1206 766 4073 1205 778 4074 1209 813 4075 1212 812 4076 1211 812 4077 1211 811 4078 1210 778 4079 1209 776 4080 1215 774 4081 1214 814 4082 1213 815 4083 1216 776 4084 1215 814 4085 1213 780 4086 1159 815 4087 1216 814 4088 1213 780 4089 1159 814 4090 1213 779 4091 1158 771 4092 1217 772 4093 1220 773 4094 1219 771 4095 1217 773 4096 1219 816 4097 1218 771 4098 1217 816 4099 1218 788 4100 1167 771 4101 1217 788 4102 1167 787 4103 1166 780 4104 1221 788 4105 1224 816 4106 1223 816 4107 1223 815 4108 1222 780 4109 1221 578 4110 1225 951 4111 1445 815 4112 1226 723 4113 1094 805 4114 1229 792 4115 1174 792 4116 1174 722 4117 1093 723 4118 1094 789 4119 1233 790 4120 1232 791 4121 1231 804 4122 1186 789 4123 1233 791 4124 1231 803 4125 1185 804 4126 1186 791 4127 1231 803 4128 1185 791 4129 1231 817 4130 1230 818 4131 1234 806 4132 1237 803 4133 1236 803 4134 1236 817 4135 1235 818 4136 1234 794 4137 1238 793 4138 1241 792 4139 1240 794 4140 1238 792 4141 1240 805 4142 1187 794 4143 1238 805 4144 1187 806 4145 1188 794 4146 1238 806 4147 1188 818 4148 1239 814 4149 1243 774 4150 1152 775 4151 1153 775 4152 1153 343 4153 1242 814 4154 1243 816 4155 1244 773 4156 1249 729 4157 1248 727 4158 1247 794 4159 1246 818 4160 1245 729 4161 1248 727 4162 1247 818 4163 1245 816 4164 1244 729 4165 1248 818 4166 1245 729 4167 1248 726 4168 1250 727 4169 1247 816 4170 1244 818 4171 1245 578 4172 1225 817 4173 1251 791 4174 1254 551 4175 1253 551 4176 1253 582 4177 1252 817 4178 1251 747 4179 1258 820 4180 1257 819 4181 1256 819 4182 1256 749 4183 1255 747 4184 1258 819 4185 1256 820 4186 1257 783 4187 1260 783 4188 1260 781 4189 1259 819 4190 1256 742 4191 1262 720 4192 1091 721 4193 1092 721 4194 1092 745 4195 1261 742 4196 1262 716 4197 1087 771 4198 1149 787 4199 1263 787 4200 1263 719 4201 1090 716 4202 1087 783 4203 1260 820 4204 1257 821 4205 1265 821 4206 1265 785 4207 1264 783 4208 1260 821 4209 1265 820 4210 1257 747 4211 1258 747 4212 1258 745 4213 1261 821 4214 1265 749 4215 1255 819 4216 1256 811 4217 1210 811 4218 1210 751 4219 1266 749 4220 1255 811 4221 1210 819 4222 1256 781 4223 1259 781 4224 1259 778 4225 1209 811 4226 1210 779 4227 1268 822 4228 1267 813 4229 1212 813 4230 1212 778 4231 1209 779 4232 1268 751 4233 1266 823 4234 1269 332 4235 1189 332 4236 1189 753 4237 1190 751 4238 1266 785 4239 1264 824 4240 1270 719 4241 1090 719 4242 1090 787 4243 1263 785 4244 1264 824 4245 1270 825 4246 1271 718 4247 1089 718 4248 1089 719 4249 1090 824 4250 1270 825 4251 1271 826 4252 1272 723 4253 1094 723 4254 1094 718 4255 1089 825 4256 1271 826 4257 1272 796 4258 1273 805 4259 1229 805 4260 1229 723 4261 1094 826 4262 1272 785 4263 1264 821 4264 1265 827 4265 1274 827 4266 1274 824 4267 1270 785 4268 1264 827 4269 1274 828 4270 1275 825 4271 1271 825 4272 1271 824 4273 1270 827 4274 1274 828 4275 1275 829 4276 1276 826 4277 1272 826 4278 1272 825 4279 1271 828 4280 1275 809 4281 1200 795 4282 1277 796 4283 1273 796 4284 1273 808 4285 1199 809 4286 1200 761 4287 1201 770 4288 1279 830 4289 1278 830 4290 1278 809 4291 1200 761 4292 1201 830 4293 1278 800 4294 1280 795 4295 1277 795 4296 1277 809 4297 1200 830 4298 1278 829 4299 1276 808 4300 1199 796 4301 1273 796 4302 1273 826 4303 1272 829 4304 1276 715 4305 1086 712 4306 1083 763 4307 1281 763 4308 1281 760 4309 1198 715 4310 1086 808 4311 1199 829 4312 1276 715 4313 1086 715 4314 1086 760 4315 1198 808 4316 1199 829 4317 1276 828 4318 1275 714 4319 1085 714 4320 1085 715 4321 1086 829 4322 1276 714 4323 1085 828 4324 1275 827 4325 1274 827 4326 1274 721 4327 1092 714 4328 1085 745 4329 1261 721 4330 1092 827 4331 1274 827 4332 1274 821 4333 1265 745 4334 1261 742 4335 1262 737 4336 1108 730 4337 1101 730 4338 1101 720 4339 1091 742 4340 1262 720 4341 1091 730 4342 1101 731 4343 1102 731 4344 1102 713 4345 1084 720 4346 1091 731 4347 1102 734 4348 1105 712 4349 1083 712 4350 1083 713 4351 1084 731 4352 1102 734 4353 1105 756 4354 1132 763 4355 1281 763 4356 1281 712 4357 1083 734 4358 1105 595 4359 1285 596 4360 1284 831 4361 1283 831 4362 1283 768 4363 1282 595 4364 1285 548 4365 1171 789 4366 1168 804 4367 1287 804 4368 1287 598 4369 1286 548 4370 1171 800 4371 1280 830 4372 1278 831 4373 1283 831 4374 1283 801 4375 1288 800 4376 1280 831 4377 1283 830 4378 1278 770 4379 1279 770 4380 1279 768 4381 1282 831 4382 1283 765 4383 1290 599 4384 1289 595 4385 1285 595 4386 1285 768 4387 1282 765 4388 1290 765 4389 1290 754 4390 1128 514 4391 1129 514 4392 1129 599 4393 1289 765 4394 1290 801 4395 1288 600 4396 1291 598 4397 1286 598 4398 1286 804 4399 1287 801 4400 1288 801 4401 1288 831 4402 1283 596 4403 1284 596 4404 1284 600 4405 1291 801 4406 1288 814 4407 1243 343 4408 1242 822 4409 1267 822 4410 1267 779 4411 1268 814 4412 1243 751 4413 1266 811 4414 1210 812 4415 1211 812 4416 1211 823 4417 1269 751 4418 1266 818 4419 1245 817 4420 1251 578 4421 1225 578 4422 1225 815 4423 1226 816 4424 1244 817 4425 1251 582 4426 1252 578 4427 1225 777 4428 1293 786 4429 1292 788 4430 1224 788 4431 1224 780 4432 1221 777 4433 1293 782 4434 1295 784 4435 1294 786 4436 1292 786 4437 1292 777 4438 1293 782 4439 1295 746 4440 1299 748 4441 1298 750 4442 1297 750 4443 1297 744 4444 1296 746 4445 1299 744 4446 1296 750 4447 1297 752 4448 1197 752 4449 1197 741 4450 1194 744 4451 1296 767 4452 1301 759 4453 1300 762 4454 1207 762 4455 1207 764 4456 1208 767 4457 1301 769 4458 1303 758 4459 1302 759 4460 1300 759 4461 1300 767 4462 1301 769 4463 1303 797 4464 1305 802 4465 1304 803 4466 1236 803 4467 1236 806 4468 1237 797 4469 1305 798 4470 1307 799 4471 1306 802 4472 1304 802 4473 1304 797 4474 1305 798 4475 1307 835 4476 1311 834 4477 1310 949 4478 1309 949 4479 1309 832 4480 1308 835 4481 1311 837 4482 1313 950 4483 1312 834 4484 1310 834 4485 1310 835 4486 1311 837 4487 1313 838 4488 1314 841 4489 1317 840 4490 1316 840 4491 1316 839 4492 1315 838 4493 1314 843 4494 1319 842 4495 1318 845 4496 1321 845 4497 1321 844 4498 1320 843 4499 1319 846 4500 1322 849 4501 1325 848 4502 1324 848 4503 1324 847 4504 1323 846 4505 1322 850 4506 1326 853 4507 1329 852 4508 1328 852 4509 1328 851 4510 1327 850 4511 1326 839 4512 1315 850 4513 1326 851 4514 1327 851 4515 1327 838 4516 1314 839 4517 1315 854 4518 1330 846 4519 1322 847 4520 1323 847 4521 1323 855 4522 1331 854 4523 1330 848 4524 1324 849 4525 1325 840 4526 1316 840 4527 1316 841 4528 1317 848 4529 1324 853 4530 1329 844 4531 1320 845 4532 1321 845 4533 1321 852 4534 1328 853 4535 1329 858 4536 1334 857 4537 1333 856 4538 1332 856 4539 1332 859 4540 1335 858 4541 1334 861 4542 1337 860 4543 1336 863 4544 1339 863 4545 1339 862 4546 1338 861 4547 1337 866 4548 1342 865 4549 1341 864 4550 1340 864 4551 1340 867 4552 1343 866 4553 1342 870 4554 1346 869 4555 1345 868 4556 1344 868 4557 1344 871 4558 1347 870 4559 1346 874 4560 1350 873 4561 1349 872 4562 1348 872 4563 1348 875 4564 1351 874 4565 1350 878 4566 1354 877 4567 1353 876 4568 1352 876 4569 1352 879 4570 1355 878 4571 1354 867 4572 1343 864 4573 1340 880 4574 1356 880 4575 1356 881 4576 1357 867 4577 1343 883 4578 1359 882 4579 1358 885 4580 1361 885 4581 1361 884 4582 1360 883 4583 1359 885 4584 1364 882 4585 1363 886 4586 1362 886 4587 1362 887 4588 1365 885 4589 1364 859 4590 1335 856 4591 1332 888 4592 1366 888 4593 1366 889 4594 1367 859 4595 1335 887 4596 1365 886 4597 1362 860 4598 1336 860 4599 1336 861 4600 1337 887 4601 1365 891 4602 1369 890 4603 1368 877 4604 1353 877 4605 1353 878 4606 1354 891 4607 1369 875 4608 1351 872 4609 1348 892 4610 1370 892 4611 1370 893 4612 1371 875 4613 1351 862 4614 1338 863 4615 1339 873 4616 1349 873 4617 1349 874 4618 1350 862 4619 1338 879 4620 1355 876 4621 1352 857 4622 1333 857 4623 1333 858 4624 1334 879 4625 1355 895 4626 1373 894 4627 1372 869 4628 1345 869 4629 1345 870 4630 1346 895 4631 1373 889 4632 1367 888 4633 1366 894 4634 1372 894 4635 1372 895 4636 1373 889 4637 1367 839 4638 1315 840 4639 1316 863 4640 1339 863 4641 1339 860 4642 1336 839 4643 1315 841 4644 1317 838 4645 1314 856 4646 1332 856 4647 1332 857 4648 1333 841 4649 1317 896 4650 1374 843 4651 1319 844 4652 1320 844 4653 1320 897 4654 1375 896 4655 1374 869 4656 1345 845 4657 1321 842 4658 1318 842 4659 1318 868 4660 1344 869 4661 1345 847 4662 1323 848 4663 1324 876 4664 1352 876 4665 1352 877 4666 1353 847 4667 1323 849 4668 1325 846 4669 1322 872 4670 1348 872 4671 1348 873 4672 1349 849 4673 1325 851 4674 1327 852 4675 1328 894 4676 1372 894 4677 1372 888 4678 1366 851 4679 1327 838 4680 1314 851 4681 1327 888 4682 1366 888 4683 1366 856 4684 1332 838 4685 1314 850 4686 1326 839 4687 1315 860 4688 1336 860 4689 1336 886 4690 1362 850 4691 1326 855 4692 1331 847 4693 1323 877 4694 1353 877 4695 1353 890 4696 1368 855 4697 1331 872 4698 1348 846 4699 1322 854 4700 1330 854 4701 1330 892 4702 1370 872 4703 1348 876 4704 1352 848 4705 1324 841 4706 1317 841 4707 1317 857 4708 1333 876 4709 1352 863 4710 1339 840 4711 1316 849 4712 1325 849 4713 1325 873 4714 1349 863 4715 1339 852 4716 1328 845 4717 1321 869 4718 1345 869 4719 1345 894 4720 1372 852 4721 1328 853 4722 1329 886 4723 1362 897 4724 1375 880 4725 1376 883 4726 1359 884 4727 1360 884 4728 1360 881 4729 1377 880 4730 1376 865 4731 1341 896 4732 1374 897 4733 1375 897 4734 1375 864 4735 1340 865 4736 1341 864 4737 1340 897 4738 1375 883 4739 1378 883 4740 1378 880 4741 1356 864 4742 1340 897 4743 1375 844 4744 1320 853 4745 1329 853 4746 1329 850 4747 1326 886 4748 1362 882 4749 1363 883 4750 1378 897 4751 1375 897 4752 1375 886 4753 1362 882 4754 1363 898 4755 1379 901 4756 1382 900 4757 1381 900 4758 1381 899 4759 1380 898 4760 1379 843 4761 1386 903 4762 1385 902 4763 1384 902 4764 1384 842 4765 1383 843 4766 1386 904 4767 1387 907 4768 1390 906 4769 1389 906 4770 1389 905 4771 1388 904 4772 1387 908 4773 1391 911 4774 1394 910 4775 1393 910 4776 1393 909 4777 1392 908 4778 1391 901 4779 1382 898 4780 1379 911 4781 1394 911 4782 1394 908 4783 1391 901 4784 1382 854 4785 1395 855 4786 1396 907 4787 1390 907 4788 1390 904 4789 1387 854 4790 1395 906 4791 1389 899 4792 1380 900 4793 1381 900 4794 1381 905 4795 1388 906 4796 1389 909 4797 1392 910 4798 1393 902 4799 1384 902 4800 1384 903 4801 1385 909 4802 1392 914 4803 1399 913 4804 1398 912 4805 1397 912 4806 1397 915 4807 1400 914 4808 1399 919 4809 1404 918 4810 1403 917 4811 1402 917 4812 1402 916 4813 1401 919 4814 1404 866 4815 1407 921 4816 1406 920 4817 1405 920 4818 1405 865 4819 1408 866 4820 1407 922 4821 1411 871 4822 1410 868 4823 1409 868 4824 1409 923 4825 1412 922 4826 1411 926 4827 1415 925 4828 1414 924 4829 1413 924 4830 1413 927 4831 1416 926 4832 1415 930 4833 1419 929 4834 1418 928 4835 1417 928 4836 1417 931 4837 1420 930 4838 1419 921 4839 1406 836 4840 1422 932 4841 1421 932 4842 1421 920 4843 1405 921 4844 1406 935 4845 1426 934 4846 1425 833 4847 1424 833 4848 1424 933 4849 1423 935 4850 1426 833 4851 1429 937 4852 1428 936 4853 1427 936 4854 1427 933 4855 1430 833 4856 1429 913 4857 1398 939 4858 1432 938 4859 1431 938 4860 1431 912 4861 1397 913 4862 1398 937 4863 1428 919 4864 1404 916 4865 1401 916 4866 1401 936 4867 1427 937 4868 1428 891 4869 1433 930 4870 1419 931 4871 1420 931 4872 1420 890 4873 1434 891 4874 1433 925 4875 1414 893 4876 1436 892 4877 1435 892 4878 1435 924 4879 1413 925 4880 1414 918 4881 1403 926 4882 1415 927 4883 1416 927 4884 1416 917 4885 1402 918 4886 1403 929 4887 1418 914 4888 1399 915 4889 1400 915 4890 1400 928 4891 1417 929 4892 1418 940 4893 1437 922 4894 1411 923 4895 1412 923 4896 1412 941 4897 1438 940 4898 1437 939 4899 1432 940 4900 1437 941 4901 1438 941 4902 1438 938 4903 1431 939 4904 1432 901 4905 1382 916 4906 1401 917 4907 1402 917 4908 1402 900 4909 1381 901 4910 1382 899 4911 1380 915 4912 1400 912 4913 1397 912 4914 1397 898 4915 1379 899 4916 1380 896 4917 1440 942 4918 1439 903 4919 1385 903 4920 1385 843 4921 1386 896 4922 1440 923 4923 1412 868 4924 1409 842 4925 1383 842 4926 1383 902 4927 1384 923 4928 1412 907 4929 1390 931 4930 1420 928 4931 1417 928 4932 1417 906 4933 1389 907 4934 1390 905 4935 1388 927 4936 1416 924 4937 1413 924 4938 1413 904 4939 1387 905 4940 1388 911 4941 1394 938 4942 1431 941 4943 1438 941 4944 1438 910 4945 1393 911 4946 1394 898 4947 1379 912 4948 1397 938 4949 1431 938 4950 1431 911 4951 1394 898 4952 1379 908 4953 1391 936 4954 1427 916 4955 1401 916 4956 1401 901 4957 1382 908 4958 1391 855 4959 1396 890 4960 1434 931 4961 1420 931 4962 1420 907 4963 1390 855 4964 1396 924 4965 1413 892 4966 1435 854 4967 1395 854 4968 1395 904 4969 1387 924 4970 1413 928 4971 1417 915 4972 1400 899 4973 1380 899 4974 1380 906 4975 1389 928 4976 1417 917 4977 1402 927 4978 1416 905 4979 1388 905 4980 1388 900 4981 1381 917 4982 1402 910 4983 1393 941 4984 1438 923 4985 1412 923 4986 1412 902 4987 1384 910 4988 1393 909 4989 1392 942 4990 1439 936 4991 1427 932 4992 1442 836 4993 1441 934 4994 1425 934 4995 1425 935 4996 1426 932 4997 1442 865 4998 1408 920 4999 1405 942 5000 1439 942 5001 1439 896 5002 1440 865 5003 1408 920 5004 1405 932 5005 1421 935 5006 1443 935 5007 1443 942 5008 1439 920 5009 1405 942 5010 1439 909 5011 1392 903 5012 1385 909 5013 1392 936 5014 1427 908 5015 1391 933 5016 1430 936 5017 1427 942 5018 1439 942 5019 1439 935 5020 1443 933 5021 1430 299 5022 504 951 5023 1444 338 5024 506 338 5025 506 298 5026 505 299 5027 504 299 5028 1228 776 5029 1227 815 5030 1226 815 5031 1226 951 5032 1445 299 5033 1228 54 5034 188 578 5035 176 952 5036 1447 952 5037 1446 578 5038 864 575 5039 867 984 5040 1546 1073 5041 1547 978 5042 1548 984 5043 1546 978 5044 1548 982 5045 1550 983 5046 1545 984 5047 1546 982 5048 1550 1005 5049 1544 983 5050 1545 982 5051 1550 1015 5052 1464 1016 5053 1465 970 5054 1466 970 5055 1466 971 5056 1449 1015 5057 1464 1019 5058 1484 1020 5059 1495 995 5060 1501 995 5061 1501 956 5062 1455 1019 5063 1484 992 5064 1448 1023 5065 1454 1019 5066 1480 1019 5067 1480 956 5068 1483 992 5069 1448 980 5070 1553 1088 5071 1554 1008 5072 1555 981 5073 1552 980 5074 1553 1008 5075 1555 993 5076 1551 981 5077 1552 1008 5078 1555 993 5079 1551 1008 5080 1555 957 5081 1556 979 5082 1456 984 5083 1482 983 5084 1485 983 5085 1485 955 5086 1453 979 5087 1456 958 5088 1451 991 5089 1452 1094 5090 1458 1094 5091 1458 1009 5092 1460 958 5093 1451 954 5094 1486 1097 5095 1487 1098 5096 1524 1098 5097 1524 997 5098 1481 954 5099 1486 968 5100 1471 959 5101 1474 953 5102 1477 953 5103 1477 965 5104 1497 968 5105 1471 975 5106 1516 976 5107 1517 977 5108 1518 977 5109 1518 974 5110 1519 975 5111 1516 966 5112 1520 967 5113 1521 964 5114 1522 964 5115 1522 963 5116 1523 966 5117 1520 965 5118 1472 953 5119 1457 996 5120 1529 996 5121 1529 962 5122 1461 965 5123 1472 974 5124 1473 977 5125 1478 972 5126 1479 972 5127 1479 973 5128 1488 974 5129 1473 963 5130 1489 964 5131 1490 961 5132 1463 961 5133 1463 960 5134 1462 963 5135 1489 966 5136 1520 963 5137 1523 971 5138 1449 971 5139 1449 970 5140 1466 966 5141 1520 963 5142 1489 960 5143 1462 969 5144 1499 969 5145 1499 971 5146 1502 963 5147 1489 961 5148 1463 964 5149 1490 974 5150 1473 974 5151 1473 973 5152 1488 961 5153 1463 964 5154 1522 967 5155 1521 975 5156 1516 975 5157 1516 974 5158 1519 964 5159 1522 967 5160 1450 968 5161 1459 976 5162 1467 976 5163 1467 975 5164 1468 967 5165 1450 968 5166 1471 965 5167 1497 977 5168 1518 977 5169 1518 976 5170 1517 968 5171 1471 965 5172 1472 962 5173 1461 972 5174 1479 972 5175 1479 977 5176 1478 965 5177 1472 991 5178 1452 997 5179 1481 1098 5180 1524 1098 5181 1524 1094 5182 1458 991 5183 1452 994 5184 1509 957 5185 1511 1008 5186 1527 1008 5187 1527 1118 5188 1507 994 5189 1509 954 5190 1494 994 5191 1525 1118 5192 1526 1118 5193 1526 1097 5194 1491 954 5195 1494 987 5196 1493 988 5197 1496 989 5198 1503 989 5199 1503 990 5200 1504 987 5201 1493 955 5202 1558 995 5203 1559 1020 5204 1560 1020 5205 1560 979 5206 1557 955 5207 1558 971 5208 1502 969 5209 1499 1006 5210 1515 1006 5211 1515 1015 5212 1514 971 5213 1502 1023 5214 1469 992 5215 1470 959 5216 1475 1023 5217 1469 959 5218 1475 968 5219 1459 1023 5220 1469 968 5221 1459 967 5222 1450 1023 5223 1469 967 5224 1450 966 5225 1476 1023 5226 1469 966 5227 1476 1007 5228 1492 1007 5229 1492 966 5230 1476 970 5231 1498 970 5232 1498 1016 5233 1500 1007 5234 1492 981 5235 1505 993 5236 1506 982 5237 1513 982 5238 1513 985 5239 1508 981 5240 1505 982 5241 1513 978 5242 1510 986 5243 1512 986 5244 1512 985 5245 1508 982 5246 1513 1088 5247 1528 980 5248 1530 986 5249 1512 986 5250 1512 978 5251 1510 1088 5252 1528 980 5253 1553 981 5254 1552 988 5255 1561 988 5256 1561 987 5257 1562 980 5258 1553 981 5259 1565 985 5260 1566 989 5261 1503 989 5262 1503 988 5263 1567 981 5264 1565 985 5265 1566 986 5266 1568 990 5267 1504 990 5268 1504 989 5269 1503 985 5270 1566 986 5271 1568 980 5272 1569 987 5273 1570 987 5274 1570 990 5275 1504 986 5276 1568 1004 5277 1533 959 5278 1534 992 5279 1531 992 5280 1531 999 5281 1532 1004 5282 1533 1002 5283 1549 957 5284 1511 994 5285 1509 994 5286 1509 1001 5287 1541 1002 5288 1549 1001 5289 1540 994 5290 1525 954 5291 1494 954 5292 1494 999 5293 1538 1001 5294 1540 1002 5295 1564 995 5296 1559 955 5297 1558 955 5298 1558 1000 5299 1563 1002 5300 1564 1005 5301 1542 982 5302 1513 993 5303 1506 993 5304 1506 1000 5305 1539 1005 5306 1542 998 5307 1536 991 5308 1452 958 5309 1451 958 5310 1451 1003 5311 1535 998 5312 1536 998 5313 1536 953 5314 1537 959 5315 1534 959 5316 1534 1004 5317 1533 998 5318 1536 997 5319 1481 1004 5320 1533 999 5321 1532 999 5322 1532 954 5323 1486 997 5324 1481 995 5325 1501 1002 5326 1549 1001 5327 1541 1001 5328 1541 956 5329 1455 995 5330 1501 956 5331 1483 1001 5332 1540 999 5333 1538 999 5334 1538 992 5335 1448 956 5336 1483 957 5337 1572 1002 5338 1564 1000 5339 1563 1000 5340 1563 993 5341 1571 957 5342 1572 983 5343 1485 1005 5344 1542 1000 5345 1539 1000 5346 1539 955 5347 1453 983 5348 1485 953 5349 1537 998 5350 1536 1003 5351 1535 1003 5352 1535 996 5353 1543 953 5354 1537 991 5355 1452 998 5356 1536 1004 5357 1533 1004 5358 1533 997 5359 1481 991 5360 1452 1012 5361 1577 1073 5362 1576 984 5363 1575 1013 5364 1578 1012 5365 1577 984 5366 1575 1013 5367 1578 984 5368 1575 1011 5369 1574 1010 5370 1573 1013 5371 1578 1011 5372 1574 1015 5373 1580 1014 5374 1579 1017 5375 1582 1017 5376 1582 1016 5377 1581 1015 5378 1580 1019 5379 1584 1018 5380 1583 1021 5381 1586 1021 5382 1586 1020 5383 1585 1019 5384 1584 1022 5385 1587 1018 5386 1590 1019 5387 1589 1019 5388 1589 1023 5389 1588 1022 5390 1587 1024 5391 1591 1028 5392 1596 1027 5393 1595 1027 5394 1595 1145 5395 1594 1026 5396 1593 1027 5397 1595 1026 5398 1593 1025 5399 1592 1024 5400 1591 1027 5401 1595 1025 5402 1592 979 5403 1598 1029 5404 1597 1011 5405 1600 1011 5406 1600 984 5407 1599 979 5408 1598 1030 5409 1601 1033 5410 1604 1032 5411 1603 1032 5412 1603 1031 5413 1602 1030 5414 1601 1035 5415 1606 1034 5416 1605 1152 5417 1608 1152 5418 1608 1153 5419 1607 1035 5420 1606 1036 5421 1609 1039 5422 1612 1038 5423 1611 1038 5424 1611 1037 5425 1610 1036 5426 1609 1040 5427 1613 1043 5428 1616 1042 5429 1615 1042 5430 1615 1041 5431 1614 1040 5432 1613 1044 5433 1617 1047 5434 1620 1046 5435 1619 1046 5436 1619 1045 5437 1618 1044 5438 1617 1039 5439 1621 1049 5440 1624 1048 5441 1623 1048 5442 1623 1038 5443 1622 1039 5444 1621 1043 5445 1625 1051 5446 1628 1050 5447 1627 1050 5448 1627 1042 5449 1626 1043 5450 1625 1047 5451 1629 1053 5452 1632 1052 5453 1631 1052 5454 1631 1046 5455 1630 1047 5456 1629 1044 5457 1617 1017 5458 1582 1014 5459 1579 1014 5460 1579 1047 5461 1620 1044 5462 1617 1047 5463 1629 1014 5464 1634 1054 5465 1633 1054 5466 1633 1053 5467 1632 1047 5468 1629 1052 5469 1631 1051 5470 1628 1043 5471 1625 1043 5472 1625 1046 5473 1630 1052 5474 1631 1046 5475 1619 1043 5476 1616 1040 5477 1613 1040 5478 1613 1045 5479 1618 1046 5480 1619 1045 5481 1635 1040 5482 1638 1041 5483 1637 1041 5484 1637 1036 5485 1636 1045 5486 1635 1036 5487 1609 1041 5488 1614 1042 5489 1615 1042 5490 1615 1039 5491 1612 1036 5492 1609 1039 5493 1621 1042 5494 1626 1050 5495 1627 1050 5496 1627 1049 5497 1624 1039 5498 1621 1031 5499 1602 1032 5500 1603 1152 5501 1608 1152 5502 1608 1034 5503 1605 1031 5504 1602 1056 5505 1640 1055 5506 1639 1027 5507 1642 1027 5508 1642 1028 5509 1641 1056 5510 1640 1035 5511 1644 1153 5512 1643 1055 5513 1646 1055 5514 1646 1056 5515 1645 1035 5516 1644 1057 5517 1647 1060 5518 1650 1059 5519 1649 1059 5520 1649 1058 5521 1648 1057 5522 1647 1029 5523 1652 979 5524 1651 1020 5525 1654 1020 5526 1654 1021 5527 1653 1029 5528 1652 1014 5529 1634 1015 5530 1655 1006 5531 1656 1006 5532 1656 1054 5533 1633 1014 5534 1634 1023 5535 1657 1007 5536 1661 1044 5537 1660 1023 5538 1657 1044 5539 1660 1045 5540 1635 1023 5541 1657 1045 5542 1635 1036 5543 1636 1023 5544 1657 1036 5545 1636 1037 5546 1659 1023 5547 1657 1037 5548 1659 1022 5549 1658 1007 5550 1661 1016 5551 1663 1017 5552 1662 1017 5553 1662 1044 5554 1660 1007 5555 1661 1025 5556 1664 1061 5557 1667 1013 5558 1666 1013 5559 1666 1024 5560 1665 1025 5561 1664 1013 5562 1666 1061 5563 1667 1062 5564 1669 1062 5565 1669 1012 5566 1668 1013 5567 1666 1145 5568 1670 1012 5569 1668 1062 5570 1669 1062 5571 1669 1026 5572 1671 1145 5573 1670 1026 5574 1593 1057 5575 1673 1058 5576 1672 1058 5577 1672 1025 5578 1592 1026 5579 1593 1025 5580 1674 1058 5581 1676 1059 5582 1649 1059 5583 1649 1061 5584 1675 1025 5585 1674 1061 5586 1675 1059 5587 1649 1060 5588 1650 1060 5589 1650 1062 5590 1677 1061 5591 1675 1062 5592 1677 1060 5593 1650 1057 5594 1679 1057 5595 1679 1026 5596 1678 1062 5597 1677 1064 5598 1682 1063 5599 1681 1022 5600 1680 1022 5601 1680 1037 5602 1683 1064 5603 1682 1066 5604 1685 1065 5605 1684 1056 5606 1640 1056 5607 1640 1028 5608 1641 1066 5609 1685 1065 5610 1687 1063 5611 1686 1035 5612 1644 1035 5613 1644 1056 5614 1645 1065 5615 1687 1066 5616 1689 1067 5617 1688 1029 5618 1652 1029 5619 1652 1021 5620 1653 1066 5621 1689 1010 5622 1691 1067 5623 1690 1024 5624 1665 1024 5625 1665 1013 5626 1666 1010 5627 1691 1069 5628 1693 1068 5629 1692 1030 5630 1601 1030 5631 1601 1031 5632 1602 1069 5633 1693 1069 5634 1693 1064 5635 1682 1037 5636 1683 1037 5637 1683 1038 5638 1694 1069 5639 1693 1034 5640 1605 1035 5641 1606 1063 5642 1681 1063 5643 1681 1064 5644 1682 1034 5645 1605 1021 5646 1586 1018 5647 1583 1065 5648 1684 1065 5649 1684 1066 5650 1685 1021 5651 1586 1018 5652 1590 1022 5653 1587 1063 5654 1686 1063 5655 1686 1065 5656 1687 1018 5657 1590 1028 5658 1696 1024 5659 1695 1067 5660 1688 1067 5661 1688 1066 5662 1689 1028 5663 1696 1011 5664 1600 1029 5665 1597 1067 5666 1690 1067 5667 1690 1010 5668 1691 1011 5669 1600 1038 5670 1694 1048 5671 1697 1068 5672 1692 1068 5673 1692 1069 5674 1693 1038 5675 1694 1031 5676 1602 1034 5677 1605 1064 5678 1682 1064 5679 1682 1069 5680 1693 1031 5681 1602 978 5682 1702 1073 5683 1701 1072 5684 1700 1074 5685 1703 978 5686 1702 1072 5687 1700 1074 5688 1703 1072 5689 1700 1071 5690 1699 1070 5691 1698 1074 5692 1703 1071 5693 1699 1076 5694 1705 1075 5695 1704 1078 5696 1707 1078 5697 1707 1077 5698 1706 1076 5699 1705 1080 5700 1709 1079 5701 1708 1082 5702 1711 1082 5703 1711 1081 5704 1710 1080 5705 1709 1083 5706 1712 1079 5707 1715 1080 5708 1714 1080 5709 1714 1084 5710 1713 1083 5711 1712 1085 5712 1716 1089 5713 1721 1008 5714 1720 1008 5715 1720 1088 5716 1719 1087 5717 1718 1008 5718 1720 1087 5719 1718 1086 5720 1717 1085 5721 1716 1008 5722 1720 1086 5723 1717 1091 5724 1723 1090 5725 1722 1071 5726 1725 1071 5727 1725 1072 5728 1724 1091 5729 1723 1092 5730 1726 1009 5731 1729 1094 5732 1728 1094 5733 1728 1093 5734 1727 1092 5735 1726 1096 5736 1731 1095 5737 1730 1098 5738 1733 1098 5739 1733 1097 5740 1732 1096 5741 1731 1099 5742 1734 1102 5743 1737 1101 5744 1736 1101 5745 1736 1100 5746 1735 1099 5747 1734 1103 5748 1738 1106 5749 1741 1105 5750 1740 1105 5751 1740 1104 5752 1739 1103 5753 1738 1107 5754 1742 1110 5755 1745 1109 5756 1744 1109 5757 1744 1108 5758 1743 1107 5759 1742 1102 5760 1746 1112 5761 1749 1111 5762 1748 1111 5763 1748 1101 5764 1747 1102 5765 1746 1106 5766 1750 1114 5767 1753 1113 5768 1752 1113 5769 1752 1105 5770 1751 1106 5771 1750 1110 5772 1754 1116 5773 1757 1115 5774 1756 1115 5775 1756 1109 5776 1755 1110 5777 1754 1107 5778 1742 1078 5779 1707 1075 5780 1704 1075 5781 1704 1110 5782 1745 1107 5783 1742 1110 5784 1754 1075 5785 1759 1117 5786 1758 1117 5787 1758 1116 5788 1757 1110 5789 1754 1115 5790 1756 1114 5791 1753 1106 5792 1750 1106 5793 1750 1109 5794 1755 1115 5795 1756 1109 5796 1744 1106 5797 1741 1103 5798 1738 1103 5799 1738 1108 5800 1743 1109 5801 1744 1108 5802 1760 1103 5803 1763 1104 5804 1762 1104 5805 1762 1099 5806 1761 1108 5807 1760 1099 5808 1734 1104 5809 1739 1105 5810 1740 1105 5811 1740 1102 5812 1737 1099 5813 1734 1102 5814 1746 1105 5815 1751 1113 5816 1752 1113 5817 1752 1112 5818 1749 1102 5819 1746 1093 5820 1727 1094 5821 1728 1098 5822 1733 1098 5823 1733 1095 5824 1730 1093 5825 1727 1119 5826 1765 1118 5827 1764 1008 5828 1767 1008 5829 1767 1089 5830 1766 1119 5831 1765 1096 5832 1769 1097 5833 1768 1118 5834 1771 1118 5835 1771 1119 5836 1770 1096 5837 1769 1120 5838 1772 1123 5839 1775 1122 5840 1774 1122 5841 1774 1121 5842 1773 1120 5843 1772 1090 5844 1777 1091 5845 1776 1081 5846 1779 1081 5847 1779 1082 5848 1778 1090 5849 1777 1075 5850 1759 1076 5851 1780 1124 5852 1781 1124 5853 1781 1117 5854 1758 1075 5855 1759 1084 5856 1782 1125 5857 1786 1107 5858 1785 1084 5859 1782 1107 5860 1785 1108 5861 1760 1084 5862 1782 1108 5863 1760 1099 5864 1761 1084 5865 1782 1099 5866 1761 1100 5867 1784 1084 5868 1782 1100 5869 1784 1083 5870 1783 1125 5871 1786 1077 5872 1788 1078 5873 1787 1078 5874 1787 1107 5875 1785 1125 5876 1786 1086 5877 1789 1126 5878 1792 1074 5879 1791 1074 5880 1791 1085 5881 1790 1086 5882 1789 1074 5883 1791 1126 5884 1792 1127 5885 1794 1127 5886 1794 978 5887 1793 1074 5888 1791 1088 5889 1795 978 5890 1793 1127 5891 1794 1127 5892 1794 1087 5893 1796 1088 5894 1795 1087 5895 1718 1120 5896 1798 1121 5897 1797 1121 5898 1797 1086 5899 1717 1087 5900 1718 1086 5901 1799 1121 5902 1801 1122 5903 1774 1122 5904 1774 1126 5905 1800 1086 5906 1799 1126 5907 1800 1122 5908 1774 1123 5909 1775 1123 5910 1775 1127 5911 1802 1126 5912 1800 1127 5913 1802 1123 5914 1775 1120 5915 1804 1120 5916 1804 1087 5917 1803 1127 5918 1802 1129 5919 1807 1128 5920 1806 1083 5921 1805 1083 5922 1805 1100 5923 1808 1129 5924 1807 1131 5925 1810 1130 5926 1809 1119 5927 1765 1119 5928 1765 1089 5929 1766 1131 5930 1810 1130 5931 1812 1128 5932 1811 1096 5933 1769 1096 5934 1769 1119 5935 1770 1130 5936 1812 1131 5937 1814 1132 5938 1813 1090 5939 1777 1090 5940 1777 1082 5941 1778 1131 5942 1814 1070 5943 1816 1132 5944 1815 1085 5945 1790 1085 5946 1790 1074 5947 1791 1070 5948 1816 1134 5949 1818 1133 5950 1817 1092 5951 1726 1092 5952 1726 1093 5953 1727 1134 5954 1818 1134 5955 1818 1129 5956 1807 1100 5957 1808 1100 5958 1808 1101 5959 1819 1134 5960 1818 1095 5961 1730 1096 5962 1731 1128 5963 1806 1128 5964 1806 1129 5965 1807 1095 5966 1730 1082 5967 1711 1079 5968 1708 1130 5969 1809 1130 5970 1809 1131 5971 1810 1082 5972 1711 1079 5973 1715 1083 5974 1712 1128 5975 1811 1128 5976 1811 1130 5977 1812 1079 5978 1715 1089 5979 1821 1085 5980 1820 1132 5981 1813 1132 5982 1813 1131 5983 1814 1089 5984 1821 1071 5985 1725 1090 5986 1722 1132 5987 1815 1132 5988 1815 1070 5989 1816 1071 5990 1725 1101 5991 1819 1111 5992 1822 1133 5993 1817 1133 5994 1817 1134 5995 1818 1101 5996 1819 1093 5997 1727 1095 5998 1730 1129 5999 1807 1129 6000 1807 1134 6001 1818 1093 6002 1727 1072 6003 1827 1073 6004 1826 1012 6005 1825 1072 6006 1827 1012 6007 1825 1136 6008 1824 1137 6009 1828 1072 6010 1827 1136 6011 1824 1135 6012 1823 1137 6013 1828 1136 6014 1824 1076 6015 1832 1077 6016 1831 1139 6017 1830 1139 6018 1830 1138 6019 1829 1076 6020 1832 1080 6021 1836 1081 6022 1835 1141 6023 1834 1141 6024 1834 1140 6025 1833 1080 6026 1836 1142 6027 1837 1084 6028 1840 1080 6029 1839 1080 6030 1839 1140 6031 1838 1142 6032 1837 1146 6033 1845 1145 6034 1844 1027 6035 1843 1147 6036 1846 1146 6037 1845 1027 6038 1843 1143 6039 1841 1147 6040 1846 1027 6041 1843 1143 6042 1841 1027 6043 1843 1144 6044 1842 1091 6045 1850 1072 6046 1849 1137 6047 1848 1137 6048 1848 1148 6049 1847 1091 6050 1850 1149 6051 1851 1150 6052 1854 1032 6053 1853 1032 6054 1853 1033 6055 1852 1149 6056 1851 1154 6057 1858 1153 6058 1857 1152 6059 1856 1152 6060 1856 1151 6061 1855 1154 6062 1858 1155 6063 1859 1158 6064 1862 1157 6065 1861 1157 6066 1861 1156 6067 1860 1155 6068 1859 1159 6069 1863 1162 6070 1866 1161 6071 1865 1161 6072 1865 1160 6073 1864 1159 6074 1863 1163 6075 1867 1166 6076 1870 1165 6077 1869 1165 6078 1869 1164 6079 1868 1163 6080 1867 1156 6081 1871 1157 6082 1874 1168 6083 1873 1168 6084 1873 1167 6085 1872 1156 6086 1871 1160 6087 1875 1161 6088 1878 1170 6089 1877 1170 6090 1877 1169 6091 1876 1160 6092 1875 1164 6093 1879 1165 6094 1882 1172 6095 1881 1172 6096 1881 1171 6097 1880 1164 6098 1879 1163 6099 1867 1164 6100 1868 1138 6101 1829 1138 6102 1829 1139 6103 1830 1163 6104 1867 1164 6105 1879 1171 6106 1880 1173 6107 1884 1173 6108 1884 1138 6109 1883 1164 6110 1879 1172 6111 1881 1165 6112 1882 1160 6113 1875 1160 6114 1875 1169 6115 1876 1172 6116 1881 1165 6117 1869 1166 6118 1870 1159 6119 1863 1159 6120 1863 1160 6121 1864 1165 6122 1869 1166 6123 1885 1155 6124 1888 1162 6125 1887 1162 6126 1887 1159 6127 1886 1166 6128 1885 1155 6129 1859 1156 6130 1860 1161 6131 1865 1161 6132 1865 1162 6133 1866 1155 6134 1859 1156 6135 1871 1167 6136 1872 1170 6137 1877 1170 6138 1877 1161 6139 1878 1156 6140 1871 1150 6141 1854 1151 6142 1855 1152 6143 1856 1152 6144 1856 1032 6145 1853 1150 6146 1854 1174 6147 1892 1144 6148 1891 1027 6149 1890 1027 6150 1890 1055 6151 1889 1174 6152 1892 1154 6153 1896 1174 6154 1895 1055 6155 1894 1055 6156 1894 1153 6157 1893 1154 6158 1896 1175 6159 1897 1178 6160 1900 1177 6161 1899 1177 6162 1899 1176 6163 1898 1175 6164 1897 1148 6165 1904 1141 6166 1903 1081 6167 1902 1081 6168 1902 1091 6169 1901 1148 6170 1904 1138 6171 1883 1173 6172 1884 1124 6173 1906 1124 6174 1906 1076 6175 1905 1138 6176 1883 1084 6177 1907 1142 6178 1911 1158 6179 1910 1084 6180 1907 1158 6181 1910 1155 6182 1888 1084 6183 1907 1155 6184 1888 1166 6185 1885 1084 6186 1907 1166 6187 1885 1163 6188 1909 1084 6189 1907 1163 6190 1909 1125 6191 1908 1125 6192 1908 1163 6193 1909 1139 6194 1913 1139 6195 1913 1077 6196 1912 1125 6197 1908 1147 6198 1914 1143 6199 1917 1136 6200 1916 1136 6201 1916 1179 6202 1915 1147 6203 1914 1136 6204 1916 1012 6205 1919 1180 6206 1918 1180 6207 1918 1179 6208 1915 1136 6209 1916 1145 6210 1921 1146 6211 1920 1180 6212 1918 1180 6213 1918 1012 6214 1919 1145 6215 1921 1146 6216 1845 1147 6217 1846 1178 6218 1923 1178 6219 1923 1175 6220 1922 1146 6221 1845 1147 6222 1924 1179 6223 1926 1177 6224 1899 1177 6225 1899 1178 6226 1925 1147 6227 1924 1179 6228 1926 1180 6229 1927 1176 6230 1898 1176 6231 1898 1177 6232 1899 1179 6233 1926 1180 6234 1927 1146 6235 1929 1175 6236 1928 1175 6237 1928 1176 6238 1898 1180 6239 1927 1181 6240 1932 1158 6241 1931 1142 6242 1930 1142 6243 1930 1182 6244 1933 1181 6245 1932 1183 6246 1934 1144 6247 1891 1174 6248 1892 1174 6249 1892 1184 6250 1935 1183 6251 1934 1184 6252 1936 1174 6253 1895 1154 6254 1896 1154 6255 1896 1182 6256 1937 1184 6257 1936 1183 6258 1938 1141 6259 1903 1148 6260 1904 1148 6261 1904 1185 6262 1939 1183 6263 1938 1135 6264 1940 1136 6265 1916 1143 6266 1917 1143 6267 1917 1185 6268 1941 1135 6269 1940 1186 6270 1942 1150 6271 1854 1149 6272 1851 1149 6273 1851 1187 6274 1943 1186 6275 1942 1186 6276 1942 1157 6277 1944 1158 6278 1931 1158 6279 1931 1181 6280 1932 1186 6281 1942 1151 6282 1855 1181 6283 1932 1182 6284 1933 1182 6285 1933 1154 6286 1858 1151 6287 1855 1141 6288 1834 1183 6289 1934 1184 6290 1935 1184 6291 1935 1140 6292 1833 1141 6293 1834 1140 6294 1838 1184 6295 1936 1182 6296 1937 1182 6297 1937 1142 6298 1837 1140 6299 1838 1144 6300 1945 1183 6301 1938 1185 6302 1939 1185 6303 1939 1143 6304 1946 1144 6305 1945 1137 6306 1848 1135 6307 1940 1185 6308 1941 1185 6309 1941 1148 6310 1847 1137 6311 1848 1157 6312 1944 1186 6313 1942 1187 6314 1943 1187 6315 1943 1168 6316 1947 1157 6317 1944 1150 6318 1854 1186 6319 1942 1181 6320 1932 1181 6321 1932 1151 6322 1855 1150 6323 1854

+ + + + +

33 0 0 18 1 1 20 2 2 33 0 3 20 2 4 21 3 5 33 0 6 21 3 7 22 4 8 34 5 9 22 4 10 28 6 11 75 7 12 93 8 13 92 9 14 51 10 15 36 11 16 38 12 17 51 10 18 38 12 19 39 13 20 51 10 21 39 13 22 40 14 23 112 15 24 44 16 25 45 17 26 39 18 27 117 19 28 118 20 29 9 21 30 66 22 31 96 23 32 65 24 33 71 25 34 70 26 35 243 27 36 63 27 37 54 27 38 23 28 39 19 29 40 30 30 41 24 31 42 23 28 43 30 30 44 24 31 45 30 30 46 25 32 47 41 33 48 37 33 49 50 34 50 42 33 51 41 33 52 50 34 53 42 33 54 50 34 55 43 35 56 64 36 57 94 37 58 95 38 59 63 39 60 62 40 61 60 41 62 54 42 63 63 39 64 60 41 65 56 43 66 57 44 67 58 45 68 56 43 69 58 45 70 55 46 71 240 47 72 62 48 73 122 49 74 101 50 75 13 51 76 102 52 77 77 53 78 78 54 79 76 55 80 79 56 81 77 53 82 76 55 83 83 57 84 80 58 85 81 59 86 83 57 87 81 59 88 82 60 89 3 61 90 83 27 91 74 62 92 5 63 93 3 61 94 74 62 95 5 63 96 4 64 97 3 61 98 55 27 99 74 62 100 239 65 101 9 21 102 107 66 103 13 51 104 74 62 105 75 67 106 239 65 107 239 65 108 54 27 109 55 27 110 75 67 111 115 27 112 239 65 113 70 68 114 71 69 115 72 70 116 72 70 117 69 71 118 70 68 119 35 72 120 32 73 121 31 74 122 31 74 123 34 75 124 35 72 125 53 76 126 48 77 127 49 78 128 49 78 129 52 79 130 53 76 131 88 80 132 90 81 133 91 82 134 91 82 135 89 83 136 88 80 137 137 84 138 140 85 139 139 86 140 138 87 141 127 88 142 128 89 143 160 90 144 158 91 145 157 92 146 229 93 147 207 94 148 208 95 149 201 96 150 211 97 151 212 98 152 175 99 153 151 100 154 206 101 155 201 102 156 182 103 157 200 104 158 129 105 159 127 88 160 130 106 161 229 107 162 194 108 163 225 109 164 137 84 165 128 89 166 145 110 167 145 110 168 167 111 169 137 84 170 187 112 171 227 113 172 195 114 173 140 85 174 167 111 175 173 115 176 173 115 177 124 116 178 178 117 179 173 115 180 131 118 181 140 85 182 140 85 183 137 84 184 167 111 185 163 119 186 164 120 187 173 115 188 173 115 189 167 111 190 163 119 191 196 121 192 180 122 193 199 123 194 132 124 195 186 125 196 183 126 197 193 127 198 192 128 199 191 129 200 182 103 201 179 130 202 194 108 203 216 131 204 214 132 205 213 133 206 177 134 207 153 135 208 227 136 209 176 137 210 215 138 211 216 131 212 204 139 213 218 27 214 217 140 215 200 141 216 202 142 217 201 96 218 155 143 219 148 144 220 154 145 221 181 146 222 179 130 223 182 103 224 141 147 225 130 106 226 127 88 227 191 129 228 223 148 229 200 104 230 200 104 231 182 103 232 191 129 233 192 128 234 230 149 235 223 148 236 222 150 237 204 139 238 217 140 239 230 149 240 192 128 241 185 151 242 192 128 243 223 148 244 191 129 245 219 152 246 223 148 247 230 149 248 230 149 249 222 150 250 219 152 251 110 153 252 106 154 253 107 66 254 15 155 255 4 156 256 17 157 257 1 158 258 8 159 259 0 160 260 47 161 261 48 162 262 44 163 263 10 164 264 82 165 265 81 166 266 53 167 267 44 163 268 48 162 269 86 168 270 92 169 271 91 170 272 62 48 273 116 171 274 122 49 275 93 172 276 83 57 277 82 60 278 232 27 279 75 67 280 76 27 281 94 37 282 27 173 283 95 38 284 82 60 285 89 174 286 93 172 287 123 175 288 61 176 289 241 177 290 105 178 291 85 179 292 87 180 293 85 179 294 112 15 295 84 181 296 113 182 297 84 181 298 112 15 299 45 17 300 113 182 301 112 15 302 25 183 303 242 184 304 237 185 305 79 186 306 234 187 307 121 40 308 93 8 309 91 82 310 92 9 311 199 188 312 197 189 313 196 190 314 225 191 315 228 192 316 229 93 317 213 133 318 198 193 319 199 188 320 188 194 321 201 102 322 212 195 323 221 11 324 217 11 325 218 11 326 185 151 327 193 127 328 184 196 329 162 27 330 149 197 331 161 198 332 172 199 333 169 200 334 171 201 335 147 202 336 145 203 337 148 144 338 152 204 339 171 201 340 151 100 341 209 205 342 177 134 343 227 136 344 12 206 345 109 207 346 8 208 347 14 209 348 100 210 349 10 164 350 4 156 351 16 211 352 17 157 353 10 164 354 17 157 355 14 209 356 17 157 357 11 212 358 14 209 359 73 213 360 56 43 361 55 46 362 6 214 363 1 158 364 2 215 365 21 216 366 0 160 367 8 159 368 76 217 369 119 218 370 232 219 371 25 32 372 31 220 373 29 221 374 29 221 375 32 222 376 26 223 377 52 224 378 40 14 379 46 225 380 53 167 381 46 225 382 45 226 383 5 227 384 57 228 385 16 211 386 67 229 387 68 230 388 61 231 389 24 232 390 236 233 391 23 234 392 71 25 393 66 235 394 72 236 395 43 35 396 49 237 397 47 161 398 87 238 399 88 239 400 89 174 401 90 240 402 86 168 403 91 170 404 61 176 405 240 47 406 241 177 407 237 185 408 24 241 409 25 183 410 105 178 411 44 16 412 104 242 413 37 243 414 51 244 415 50 245 416 238 246 417 67 247 418 123 175 419 69 248 420 65 24 421 70 26 422 35 249 423 26 223 424 32 222 425 5 63 426 55 27 427 58 27 428 77 250 429 119 218 430 78 251 431 97 252 432 26 253 433 94 37 434 27 173 435 96 23 436 95 38 437 99 254 438 103 255 439 100 210 440 102 52 441 7 256 442 103 255 443 82 165 444 103 255 445 87 180 446 103 255 447 105 178 448 87 180 449 108 257 450 22 258 451 109 207 452 107 66 453 7 256 454 13 51 455 96 23 456 108 257 457 9 21 458 111 259 459 12 206 460 6 260 461 43 261 462 6 260 463 42 262 464 46 263 465 233 264 466 113 182 467 120 265 468 40 266 469 114 267 470 114 267 471 39 268 472 118 269 473 233 264 474 86 270 475 113 182 476 33 271 477 19 272 478 18 273 479 238 246 480 29 274 481 97 252 482 30 275 483 34 75 484 31 74 485 51 244 486 49 78 487 50 245 488 135 276 489 133 277 490 136 278 491 128 89 492 139 86 493 138 87 494 134 279 495 195 114 496 133 277 497 129 105 498 135 276 499 136 278 500 139 86 501 131 118 502 132 124 503 144 280 504 142 281 505 141 282 506 150 27 507 124 116 508 149 197 509 124 116 510 205 27 511 204 139 512 143 283 513 157 92 514 142 281 515 156 284 516 154 145 517 153 135 518 131 118 519 178 117 520 186 125 521 183 126 522 151 285 523 132 124 524 157 286 525 134 279 526 135 276 527 209 287 528 188 194 529 212 195 530 171 288 531 138 87 532 139 86 533 158 289 534 174 290 535 134 279 536 227 113 537 133 277 538 195 114 539 130 106 540 157 286 541 135 276 542 184 196 543 229 107 544 208 291 545 164 120 546 149 197 547 173 115 548 184 196 549 186 125 550 185 151 551 169 292 552 127 88 553 138 87 554 190 293 555 195 114 556 174 290 557 159 294 558 176 137 559 158 91 560 165 33 561 163 33 562 166 33 563 167 111 564 166 295 565 163 119 566 145 203 567 168 296 568 167 297 569 185 151 570 178 117 571 230 149 572 183 126 573 208 291 574 206 298 575 180 122 576 213 299 577 199 123 578 153 300 579 136 278 580 133 277 581 225 109 582 179 130 583 196 121 584 216 301 585 174 290 586 176 302 587 230 149 588 124 116 589 204 139 590 80 303 591 3 304 592 15 155 593 35 249 594 28 6 595 27 305 596 98 306 597 102 52 598 99 254 599 2 215 600 42 307 601 6 214 602 98 306 603 56 308 604 59 309 605 15 155 606 81 166 607 80 303 608 85 310 609 90 240 610 88 239 611 60 41 612 68 230 613 54 42 614 54 311 615 73 312 616 55 313 617 76 55 618 92 169 619 79 56 620 96 23 621 64 36 622 95 38 623 65 314 624 97 252 625 94 37 626 59 309 627 101 50 628 98 306 629 72 236 630 59 315 631 73 213 632 43 261 633 106 154 634 111 259 635 106 154 636 105 178 637 7 256 638 108 257 639 110 153 640 107 66 641 8 208 642 22 258 643 21 316 644 16 211 645 56 308 646 11 212 647 121 40 648 77 250 649 79 186 650 68 317 651 72 70 652 73 312 653 189 318 654 187 112 655 190 293 656 182 103 657 193 127 658 191 129 659 181 146 660 189 318 661 180 122 662 170 319 663 141 282 664 169 200 665 196 190 666 226 320 667 225 191 668 200 141 669 224 321 670 203 322 671 136 278 672 148 323 673 129 105 674 165 33 675 161 33 676 164 33 677 208 95 678 175 324 679 206 325 680 212 98 681 210 326 682 209 205 683 219 11 684 221 11 685 220 11 686 223 148 687 220 327 688 224 328 689 213 299 690 190 293 691 216 301 692 171 288 693 132 124 694 151 285 695 11 212 696 99 254 697 14 209 698 54 27 699 239 65 700 243 27 701 148 323 702 128 89 703 129 105 704 277 329 705 264 330 706 262 331 707 277 329 708 265 332 709 264 330 710 277 329 711 266 4 712 265 332 713 278 333 714 266 4 715 277 329 716 337 334 717 319 335 718 336 336 719 295 337 720 282 338 721 280 33 722 295 337 723 283 339 724 282 338 725 295 337 726 284 340 727 283 339 728 356 341 729 288 342 730 348 343 731 117 344 732 283 345 733 118 346 734 253 347 735 310 348 736 345 349 737 315 350 738 309 351 739 314 352 740 307 27 741 475 27 742 298 27 743 267 353 744 274 354 745 263 355 746 268 356 747 274 354 748 267 353 749 268 356 750 269 357 751 274 354 752 285 11 753 294 358 754 281 11 755 286 11 756 294 358 757 285 11 758 286 11 759 287 359 760 294 358 761 308 360 762 338 361 763 309 362 764 307 40 765 304 363 766 306 40 767 298 40 768 304 363 769 307 40 770 300 364 771 302 365 772 301 366 773 300 364 774 299 367 775 302 365 776 306 368 777 472 369 778 359 370 779 257 371 780 345 349 781 346 372 782 321 373 783 320 374 784 322 375 785 323 376 786 320 374 787 321 373 788 327 377 789 325 378 790 324 379 791 327 377 792 326 380 793 325 378 794 247 381 795 318 382 796 327 27 797 249 381 798 318 382 799 247 381 800 249 381 801 247 381 802 248 383 803 299 27 804 239 384 805 318 382 806 253 347 807 351 385 808 352 386 809 318 382 810 239 384 811 319 387 812 239 384 813 299 27 814 298 27 815 319 387 816 239 384 817 115 27 818 314 388 819 316 389 820 315 390 821 316 389 822 314 388 823 313 391 824 279 392 825 275 393 826 276 394 827 275 393 828 279 392 829 278 395 830 297 396 831 293 397 832 292 398 833 293 397 834 297 396 835 296 399 836 332 400 837 335 401 838 334 402 839 335 401 840 332 400 841 333 403 842 374 404 843 376 405 844 377 406 845 375 407 846 365 408 847 364 409 848 395 410 849 397 411 850 394 412 851 444 413 852 466 414 853 445 100 854 448 143 855 438 144 856 449 415 857 388 416 858 412 417 859 443 325 860 438 418 861 419 419 862 418 420 863 366 421 864 364 409 865 365 408 866 466 422 867 431 423 868 430 424 869 374 404 870 382 425 871 365 408 872 382 425 873 374 404 874 404 426 875 464 427 876 424 428 877 432 429 878 377 406 879 410 430 880 404 426 881 410 430 882 361 431 883 386 432 884 410 430 885 377 406 886 368 433 887 377 406 888 404 426 889 374 404 890 400 434 891 410 430 892 401 435 893 410 430 894 400 434 895 404 426 896 433 436 897 417 437 898 416 438 899 369 439 900 423 440 901 368 433 902 430 424 903 428 441 904 429 442 905 419 419 906 431 423 907 416 438 908 451 443 909 453 444 910 450 445 911 390 446 912 414 447 913 464 328 914 452 294 915 413 27 916 453 444 917 455 27 918 441 432 919 454 448 920 439 202 921 437 449 922 438 144 923 385 450 924 392 451 925 391 452 926 418 420 927 416 438 928 417 437 929 378 453 930 367 454 931 379 455 932 428 441 933 437 456 934 460 457 935 437 456 936 428 441 937 419 419 938 429 442 939 460 457 940 467 458 941 459 435 942 441 432 943 467 458 944 467 458 945 422 459 946 429 442 947 429 442 948 428 441 949 460 457 950 456 460 951 467 458 952 460 457 953 467 458 954 456 460 955 459 435 956 354 461 957 350 462 958 355 463 959 259 464 960 248 465 961 247 466 962 245 467 963 252 468 964 256 469 965 291 470 966 292 471 967 293 472 968 326 473 969 254 474 970 325 166 971 288 475 972 297 476 973 292 471 974 330 477 975 336 478 976 323 376 977 358 479 978 306 368 979 359 370 980 337 480 981 327 377 982 318 11 983 232 27 984 319 387 985 115 27 986 338 361 987 271 481 988 270 482 989 333 483 990 326 380 991 337 480 992 360 484 993 305 485 994 311 486 995 329 487 996 349 488 997 331 489 998 329 487 999 356 341 1000 348 343 1001 357 490 1002 328 491 1003 330 492 1004 289 493 1005 357 490 1006 290 494 1007 474 495 1008 269 496 1009 470 497 1010 234 40 1011 323 40 1012 121 40 1013 336 336 1014 333 403 1015 337 334 1016 434 498 1017 436 499 1018 433 500 1019 465 501 1020 462 502 1021 466 414 1022 435 503 1023 450 445 1024 436 499 1025 425 504 1026 438 418 1027 418 420 1028 458 33 1029 454 33 1030 459 33 1031 430 424 1032 422 459 1033 421 505 1034 386 432 1035 399 27 1036 398 448 1037 406 506 1038 409 507 1039 408 508 1040 382 509 1041 384 510 1042 385 450 1043 408 508 1044 389 511 1045 388 416 1046 414 447 1047 446 512 1048 464 328 1049 256 513 1050 353 514 1051 354 461 1052 344 515 1053 258 516 1054 254 474 1055 260 517 1056 248 465 1057 261 518 1058 254 474 1059 261 518 1060 259 464 1061 255 519 1062 261 518 1063 258 516 1064 317 520 1065 300 364 1066 303 521 1067 250 522 1068 245 467 1069 256 469 1070 265 523 1071 244 524 1072 264 525 1073 320 526 1074 119 527 1075 322 528 1076 269 357 1077 275 529 1078 274 354 1079 273 530 1080 276 531 1081 275 529 1082 296 532 1083 284 340 1084 295 337 1085 297 476 1086 290 533 1087 296 532 1088 249 534 1089 301 535 1090 302 536 1091 312 537 1092 311 538 1093 305 539 1094 469 540 1095 268 541 1096 267 542 1097 315 350 1098 310 543 1099 308 544 1100 287 359 1101 293 472 1102 294 358 1103 332 545 1104 331 546 1105 333 483 1106 334 547 1107 330 477 1108 328 548 1109 472 369 1110 305 485 1111 473 549 1112 268 550 1113 470 497 1114 269 496 1115 349 488 1116 288 342 1117 291 551 1118 295 552 1119 281 553 1120 294 554 1121 471 555 1122 311 486 1123 341 556 1124 313 557 1125 309 351 1126 311 538 1127 270 558 1128 279 559 1129 276 531 1130 249 381 1131 299 27 1132 318 382 1133 119 527 1134 321 560 1135 322 528 1136 341 556 1137 270 482 1138 273 561 1139 271 481 1140 340 562 1141 272 563 1142 347 564 1143 343 565 1144 344 515 1145 251 566 1146 346 372 1147 347 564 1148 326 473 1149 347 564 1150 344 515 1151 349 488 1152 347 564 1153 331 489 1154 352 386 1155 266 567 1156 272 563 1157 351 385 1158 251 566 1159 350 462 1160 352 386 1161 340 562 1162 253 347 1163 355 463 1164 256 513 1165 354 461 1166 287 568 1167 250 569 1168 355 463 1169 233 570 1170 290 494 1171 357 490 1172 120 571 1173 284 572 1174 290 494 1175 283 573 1176 114 574 1177 118 575 1178 233 570 1179 330 492 1180 234 40 1181 263 576 1182 277 577 1183 262 578 1184 471 555 1185 273 561 1186 474 495 1187 274 579 1188 278 395 1189 277 577 1190 293 397 1191 295 552 1192 294 554 1193 372 580 1194 370 581 1195 371 582 1196 365 408 1197 376 405 1198 374 404 1199 371 582 1200 432 429 1201 411 583 1202 366 421 1203 372 580 1204 367 454 1205 368 433 1206 376 405 1207 369 439 1208 379 584 1209 381 585 1210 378 586 1211 361 431 1212 387 27 1213 386 432 1214 442 27 1215 361 431 1216 441 432 1217 394 412 1218 380 587 1219 379 584 1220 391 452 1221 393 588 1222 390 446 1223 368 433 1224 415 589 1225 410 430 1226 420 590 1227 388 591 1228 443 592 1229 394 593 1230 371 582 1231 395 594 1232 446 595 1233 425 504 1234 424 428 1235 408 596 1236 375 407 1237 406 597 1238 395 594 1239 411 583 1240 413 598 1241 370 581 1242 464 427 1243 432 429 1244 367 454 1245 394 593 1246 379 455 1247 466 422 1248 421 505 1249 445 599 1250 401 435 1251 386 432 1252 398 448 1253 421 505 1254 423 440 1255 420 590 1256 406 597 1257 364 409 1258 378 453 1259 427 600 1260 432 429 1261 424 428 1262 413 27 1263 396 601 1264 395 410 1265 400 11 1266 402 11 1267 403 11 1268 404 426 1269 403 602 1270 405 328 1271 382 509 1272 405 603 1273 383 322 1274 422 459 1275 415 589 1276 423 440 1277 420 590 1278 445 599 1279 421 505 1280 417 437 1281 450 604 1282 426 605 1283 390 606 1284 373 607 1285 391 608 1286 462 609 1287 416 438 1288 431 423 1289 453 610 1290 411 583 1291 427 600 1292 467 458 1293 361 431 1294 415 589 1295 324 303 1296 247 466 1297 327 611 1298 279 559 1299 272 612 1300 278 333 1301 346 372 1302 342 613 1303 343 565 1304 246 614 1305 286 615 1306 285 616 1307 300 617 1308 342 613 1309 303 618 1310 259 464 1311 325 166 1312 254 474 1313 329 619 1314 334 547 1315 328 548 1316 304 363 1317 312 537 1318 305 539 1319 317 620 1320 298 621 1321 299 622 1322 320 374 1323 336 478 1324 319 33 1325 340 562 1326 308 360 1327 310 348 1328 309 362 1329 341 556 1330 311 486 1331 345 349 1332 303 618 1333 342 613 1334 316 623 1335 303 521 1336 310 543 1337 287 568 1338 350 462 1339 291 551 1340 350 462 1341 349 488 1342 291 551 1343 352 386 1344 354 461 1345 353 514 1346 252 624 1347 266 567 1348 353 514 1349 260 517 1350 300 617 1351 301 535 1352 321 560 1353 121 40 1354 323 40 1355 316 389 1356 312 625 1357 317 620 1358 426 605 1359 424 428 1360 425 504 1361 430 424 1362 419 419 1363 428 441 1364 418 420 1365 426 605 1366 425 504 1367 378 586 1368 407 626 1369 406 506 1370 463 627 1371 433 500 1372 462 502 1373 437 449 1374 461 628 1375 460 297 1376 373 607 1377 385 629 1378 391 608 1379 402 11 1380 398 11 1381 399 11 1382 412 99 1383 445 100 1384 443 101 1385 447 630 1386 449 415 1387 446 512 1388 458 33 1389 456 33 1390 457 33 1391 460 457 1392 457 631 1393 456 460 1394 450 604 1395 427 600 1396 426 605 1397 369 439 1398 408 596 1399 388 591 1400 343 565 1401 255 519 1402 258 516 1403 298 27 1404 475 27 1405 239 384 1406 385 629 1407 365 408 1408 382 425 1409 509 632 1410 496 633 1411 494 40 1412 509 632 1413 497 634 1414 496 633 1415 509 632 1416 498 635 1417 497 634 1418 510 636 1419 498 635 1420 509 632 1421 569 637 1422 551 638 1423 568 639 1424 527 640 1425 514 641 1426 512 11 1427 527 640 1428 515 642 1429 514 641 1430 527 640 1431 516 14 1432 515 642 1433 588 643 1434 520 644 1435 580 645 1436 592 646 1437 515 647 1438 593 648 1439 485 649 1440 542 22 1441 577 650 1442 547 651 1443 541 652 1444 546 653 1445 539 27 1446 243 27 1447 530 27 1448 499 654 1449 506 655 1450 495 656 1451 500 657 1452 506 655 1453 499 654 1454 500 657 1455 501 658 1456 506 655 1457 517 659 1458 526 660 1459 513 33 1460 518 661 1461 526 660 1462 517 659 1463 518 661 1464 519 35 1465 526 660 1466 540 662 1467 570 663 1468 541 314 1469 539 664 1470 536 665 1471 538 331 1472 530 666 1473 536 665 1474 539 664 1475 532 667 1476 534 668 1477 533 669 1478 532 667 1479 531 670 1480 534 668 1481 538 48 1482 240 671 1483 122 49 1484 489 672 1485 577 650 1486 578 673 1487 553 674 1488 552 675 1489 554 676 1490 555 677 1491 552 675 1492 553 674 1493 559 678 1494 557 679 1495 556 680 1496 559 678 1497 558 681 1498 557 679 1499 479 682 1500 550 683 1501 559 27 1502 481 684 1503 550 683 1504 479 682 1505 481 684 1506 479 682 1507 480 685 1508 531 27 1509 239 686 1510 550 683 1511 485 649 1512 583 687 1513 584 688 1514 550 683 1515 239 686 1516 551 689 1517 239 686 1518 531 27 1519 530 27 1520 551 689 1521 239 686 1522 591 27 1523 546 690 1524 548 691 1525 547 692 1526 548 691 1527 546 690 1528 545 693 1529 511 694 1530 507 695 1531 508 696 1532 507 695 1533 511 694 1534 510 697 1535 529 698 1536 525 699 1537 524 700 1538 525 699 1539 529 698 1540 528 701 1541 564 702 1542 567 703 1543 566 704 1544 567 703 1545 564 702 1546 565 705 1547 610 706 1548 612 707 1549 613 708 1550 611 709 1551 601 710 1552 600 711 1553 631 712 1554 633 90 1555 630 713 1556 680 94 1557 702 93 1558 681 95 1559 684 97 1560 674 96 1561 685 98 1562 624 100 1563 648 99 1564 679 101 1565 674 714 1566 655 715 1567 654 716 1568 602 717 1569 600 711 1570 601 710 1571 702 718 1572 667 719 1573 666 720 1574 610 706 1575 618 721 1576 601 710 1577 618 721 1578 610 706 1579 640 722 1580 700 723 1581 660 724 1582 668 725 1583 613 708 1584 646 726 1585 640 722 1586 646 726 1587 597 727 1588 622 728 1589 646 726 1590 613 708 1591 604 729 1592 613 708 1593 640 722 1594 610 706 1595 636 730 1596 646 726 1597 637 731 1598 646 726 1599 636 730 1600 640 722 1601 669 732 1602 653 733 1603 652 734 1604 605 735 1605 659 736 1606 604 729 1607 666 720 1608 664 737 1609 665 738 1610 655 715 1611 667 719 1612 652 734 1613 687 132 1614 689 131 1615 686 739 1616 626 135 1617 650 740 1618 700 136 1619 688 138 1620 649 741 1621 689 131 1622 691 27 1623 677 742 1624 690 743 1625 675 142 1626 673 141 1627 674 96 1628 621 744 1629 628 143 1630 627 145 1631 654 716 1632 652 734 1633 653 733 1634 614 745 1635 603 746 1636 615 747 1637 664 737 1638 673 748 1639 696 749 1640 673 748 1641 664 737 1642 655 715 1643 665 738 1644 696 749 1645 703 750 1646 695 751 1647 677 742 1648 703 750 1649 703 750 1650 658 752 1651 665 738 1652 665 738 1653 664 737 1654 696 749 1655 692 753 1656 703 750 1657 696 749 1658 703 750 1659 692 753 1660 695 751 1661 586 754 1662 582 755 1663 587 756 1664 491 757 1665 480 758 1666 479 759 1667 477 760 1668 484 761 1669 488 762 1670 523 763 1671 524 764 1672 525 237 1673 558 765 1674 486 766 1675 557 767 1676 520 768 1677 529 769 1678 524 764 1679 562 770 1680 568 771 1681 555 677 1682 116 171 1683 538 48 1684 122 49 1685 569 172 1686 559 678 1687 550 33 1688 705 27 1689 551 689 1690 591 27 1691 570 663 1692 503 772 1693 502 773 1694 565 174 1695 558 681 1696 569 172 1697 123 774 1698 537 176 1699 543 775 1700 561 776 1701 581 777 1702 563 778 1703 561 776 1704 588 643 1705 580 645 1706 589 779 1707 560 780 1708 562 781 1709 521 782 1710 589 779 1711 522 783 1712 242 784 1713 501 785 1714 237 786 1715 707 787 1716 555 788 1717 596 331 1718 567 703 1719 569 637 1720 568 639 1721 670 789 1722 672 790 1723 669 791 1724 701 192 1725 698 191 1726 702 93 1727 671 792 1728 686 739 1729 672 790 1730 661 793 1731 674 714 1732 654 716 1733 694 11 1734 690 11 1735 695 11 1736 666 720 1737 658 752 1738 657 794 1739 622 728 1740 635 27 1741 634 795 1742 642 200 1743 645 199 1744 644 201 1745 618 796 1746 620 797 1747 621 744 1748 644 201 1749 625 798 1750 624 100 1751 650 740 1752 682 799 1753 700 136 1754 488 800 1755 585 801 1756 586 754 1757 576 802 1758 490 803 1759 486 766 1760 492 804 1761 480 758 1762 493 805 1763 486 766 1764 493 805 1765 491 757 1766 487 806 1767 493 805 1768 490 803 1769 549 807 1770 532 667 1771 535 808 1772 482 809 1773 477 760 1774 488 762 1775 497 216 1776 476 810 1777 496 811 1778 552 812 1779 594 813 1780 554 814 1781 501 658 1782 507 815 1783 506 655 1784 505 816 1785 508 817 1786 507 815 1787 528 224 1788 516 14 1789 527 640 1790 529 769 1791 522 818 1792 528 224 1793 481 819 1794 533 820 1795 534 821 1796 544 822 1797 543 823 1798 537 824 1799 236 825 1800 500 826 1801 499 827 1802 547 651 1803 542 828 1804 540 829 1805 519 35 1806 525 237 1807 526 660 1808 564 239 1809 563 830 1810 565 174 1811 566 831 1812 562 770 1813 560 832 1814 240 671 1815 537 176 1816 241 177 1817 500 833 1818 237 786 1819 501 785 1820 581 777 1821 520 644 1822 523 834 1823 527 835 1824 513 836 1825 526 837 1826 238 838 1827 543 775 1828 573 839 1829 545 840 1830 541 652 1831 543 823 1832 502 841 1833 511 842 1834 508 817 1835 481 684 1836 531 27 1837 550 683 1838 594 813 1839 553 843 1840 554 814 1841 573 839 1842 502 773 1843 505 844 1844 503 772 1845 572 845 1846 504 846 1847 579 847 1848 575 848 1849 576 802 1850 483 849 1851 578 673 1852 579 847 1853 558 765 1854 579 847 1855 576 802 1856 581 777 1857 579 847 1858 563 778 1859 584 688 1860 498 258 1861 504 846 1862 583 687 1863 483 849 1864 582 755 1865 584 688 1866 572 845 1867 485 649 1868 587 756 1869 488 800 1870 586 754 1871 519 850 1872 482 851 1873 587 756 1874 706 852 1875 522 783 1876 589 779 1877 595 853 1878 516 854 1879 522 783 1880 515 855 1881 590 856 1882 593 857 1883 706 852 1884 562 781 1885 707 787 1886 495 858 1887 509 859 1888 494 860 1889 238 838 1890 505 844 1891 242 784 1892 506 861 1893 510 697 1894 509 859 1895 525 699 1896 527 835 1897 526 837 1898 608 862 1899 606 863 1900 607 864 1901 601 710 1902 612 707 1903 610 706 1904 607 864 1905 668 725 1906 647 865 1907 602 717 1908 608 862 1909 603 746 1910 604 729 1911 612 707 1912 605 735 1913 615 866 1914 617 867 1915 614 868 1916 597 727 1917 623 27 1918 622 728 1919 678 27 1920 597 727 1921 677 742 1922 630 713 1923 616 869 1924 615 866 1925 627 145 1926 629 870 1927 626 135 1928 604 729 1929 651 871 1930 646 726 1931 656 872 1932 624 873 1933 679 874 1934 630 875 1935 607 864 1936 631 876 1937 682 877 1938 661 793 1939 660 724 1940 644 878 1941 611 709 1942 642 879 1943 631 876 1944 647 865 1945 649 880 1946 606 863 1947 700 723 1948 668 725 1949 603 746 1950 630 875 1951 615 747 1952 702 718 1953 657 794 1954 681 881 1955 637 731 1956 622 728 1957 634 795 1958 657 794 1959 659 736 1960 656 872 1961 642 879 1962 600 711 1963 614 745 1964 663 882 1965 668 725 1966 660 724 1967 649 741 1968 632 883 1969 631 712 1970 636 33 1971 638 33 1972 639 33 1973 640 722 1974 639 295 1975 641 328 1976 618 796 1977 641 296 1978 619 884 1979 658 752 1980 651 871 1981 659 736 1982 656 872 1983 681 881 1984 657 794 1985 653 733 1986 686 885 1987 662 886 1988 626 887 1989 609 888 1990 627 889 1991 698 890 1992 652 734 1993 667 719 1994 689 891 1995 647 865 1996 663 882 1997 703 750 1998 597 727 1999 651 871 2000 556 892 2001 479 759 2002 559 893 2003 511 842 2004 504 894 2005 510 636 2006 578 673 2007 574 895 2008 575 848 2009 478 896 2010 518 897 2011 517 898 2012 532 899 2013 574 895 2014 535 309 2015 491 757 2016 557 767 2017 486 766 2018 561 310 2019 566 831 2020 560 832 2021 536 665 2022 544 822 2023 537 824 2024 549 900 2025 530 901 2026 531 901 2027 552 675 2028 568 771 2029 551 11 2030 572 845 2031 540 662 2032 542 22 2033 541 314 2034 573 839 2035 543 775 2036 577 650 2037 535 309 2038 574 895 2039 548 902 2040 535 808 2041 542 828 2042 519 850 2043 582 755 2044 523 834 2045 582 755 2046 581 777 2047 523 834 2048 584 688 2049 586 754 2050 585 801 2051 484 903 2052 498 258 2053 585 801 2054 492 804 2055 532 899 2056 533 820 2057 553 843 2058 596 331 2059 555 788 2060 548 691 2061 544 904 2062 549 900 2063 662 886 2064 660 724 2065 661 793 2066 666 720 2067 655 715 2068 664 737 2069 654 716 2070 662 886 2071 661 793 2072 614 868 2073 643 905 2074 642 200 2075 699 320 2076 669 791 2077 698 191 2078 673 141 2079 697 321 2080 696 906 2081 609 888 2082 621 907 2083 627 889 2084 638 33 2085 634 33 2086 635 33 2087 648 324 2088 681 95 2089 679 325 2090 683 326 2091 685 98 2092 682 799 2093 694 11 2094 692 11 2095 693 11 2096 696 749 2097 693 327 2098 692 753 2099 686 885 2100 663 882 2101 662 886 2102 605 735 2103 644 878 2104 624 873 2105 575 848 2106 487 806 2107 490 803 2108 530 27 2109 243 27 2110 239 686 2111 621 907 2112 601 710 2113 618 721 2114 741 632 2115 726 40 2116 728 908 2117 741 632 2118 728 908 2119 729 909 2120 741 632 2121 729 909 2122 730 910 2123 742 911 2124 730 910 2125 736 912 2126 783 913 2127 801 914 2128 800 915 2129 759 916 2130 744 33 2131 746 917 2132 759 916 2133 746 917 2134 747 918 2135 759 916 2136 747 918 2137 748 919 2138 820 920 2139 752 921 2140 753 922 2141 747 923 2142 592 924 2143 593 925 2144 717 926 2145 774 927 2146 804 928 2147 773 929 2148 779 930 2149 778 931 2150 475 27 2151 771 27 2152 762 27 2153 731 932 2154 727 933 2155 738 934 2156 732 935 2157 731 932 2158 738 934 2159 732 935 2160 738 934 2161 733 936 2162 749 11 2163 745 11 2164 758 937 2165 750 11 2166 749 11 2167 758 937 2168 750 11 2169 758 937 2170 751 359 2171 772 938 2172 802 939 2173 803 940 2174 771 331 2175 770 331 2176 768 941 2177 762 331 2178 771 331 2179 768 941 2180 764 942 2181 765 943 2182 766 944 2183 764 942 2184 766 944 2185 763 945 2186 472 946 2187 770 368 2188 359 370 2189 809 947 2190 721 948 2191 810 949 2192 785 950 2193 786 951 2194 784 952 2195 787 953 2196 785 950 2197 784 952 2198 791 954 2199 788 955 2200 789 956 2201 791 954 2202 789 956 2203 790 957 2204 711 381 2205 791 27 2206 782 382 2207 713 958 2208 711 381 2209 782 382 2210 713 958 2211 712 383 2212 711 381 2213 763 27 2214 782 382 2215 239 959 2216 717 926 2217 815 960 2218 721 948 2219 782 382 2220 783 961 2221 239 959 2222 239 959 2223 762 27 2224 763 27 2225 783 961 2226 591 27 2227 239 959 2228 778 962 2229 779 963 2230 780 964 2231 780 964 2232 777 965 2233 778 962 2234 743 966 2235 740 967 2236 739 968 2237 739 968 2238 742 969 2239 743 966 2240 761 970 2241 756 971 2242 757 972 2243 757 972 2244 760 973 2245 761 970 2246 796 974 2247 798 975 2248 799 976 2249 799 976 2250 797 977 2251 796 974 2252 835 978 2253 838 979 2254 837 980 2255 836 981 2256 825 982 2257 826 983 2258 858 411 2259 856 410 2260 855 984 2261 927 985 2262 905 798 2263 906 100 2264 899 744 2265 909 143 2266 910 415 2267 873 417 2268 849 416 2269 904 325 2270 899 986 2271 880 987 2272 898 988 2273 827 989 2274 825 982 2275 828 990 2276 927 991 2277 892 992 2278 923 993 2279 835 978 2280 826 983 2281 843 994 2282 843 994 2283 865 995 2284 835 978 2285 885 996 2286 925 997 2287 893 998 2288 838 979 2289 865 995 2290 871 999 2291 871 999 2292 822 1000 2293 876 1001 2294 871 999 2295 829 1002 2296 838 979 2297 838 979 2298 835 978 2299 865 995 2300 861 1003 2301 862 751 2302 871 999 2303 871 999 2304 865 995 2305 861 1003 2306 894 1004 2307 878 1005 2308 897 1006 2309 830 1007 2310 884 1008 2311 881 1009 2312 891 1010 2313 890 1011 2314 889 1012 2315 880 987 2316 877 1013 2317 892 992 2318 914 444 2319 912 443 2320 911 1014 2321 875 1015 2322 851 1016 2323 925 328 2324 874 1017 2325 913 294 2326 914 444 2327 902 1018 2328 916 27 2329 915 1019 2330 898 449 2331 900 797 2332 899 744 2333 853 1020 2334 846 1021 2335 852 1022 2336 879 1023 2337 877 1013 2338 880 987 2339 839 1024 2340 828 990 2341 825 982 2342 889 1012 2343 921 1025 2344 898 988 2345 898 988 2346 880 987 2347 889 1012 2348 890 1011 2349 928 1026 2350 921 1025 2351 920 1027 2352 902 1018 2353 915 1019 2354 928 1026 2355 890 1011 2356 883 1028 2357 890 1011 2358 921 1025 2359 889 1012 2360 917 1029 2361 921 1025 2362 928 1026 2363 928 1026 2364 920 1027 2365 917 1029 2366 818 1030 2367 814 1031 2368 815 960 2369 723 1032 2370 712 1033 2371 725 1034 2372 709 1035 2373 716 1036 2374 708 1037 2375 755 470 2376 756 1038 2377 752 1039 2378 718 1040 2379 790 331 2380 789 1041 2381 761 1042 2382 752 1039 2383 756 1038 2384 794 1043 2385 800 1044 2386 799 1045 2387 770 368 2388 358 479 2389 359 370 2390 801 480 2391 791 954 2392 790 957 2393 705 27 2394 783 961 2395 784 27 2396 802 939 2397 735 1046 2398 803 940 2399 790 957 2400 797 483 2401 801 480 2402 360 1047 2403 769 485 2404 473 549 2405 813 1048 2406 793 1049 2407 795 1050 2408 793 1049 2409 820 920 2410 792 1051 2411 821 1052 2412 792 1051 2413 820 920 2414 753 922 2415 821 1052 2416 820 920 2417 733 1053 2418 474 1054 2419 470 1055 2420 787 331 2421 707 331 2422 596 331 2423 800 915 2424 797 977 2425 799 976 2426 897 1056 2427 895 1057 2428 894 1058 2429 923 502 2430 926 1059 2431 927 985 2432 911 1014 2433 896 1060 2434 897 1056 2435 886 1061 2436 899 986 2437 910 1062 2438 919 33 2439 915 33 2440 916 33 2441 883 1028 2442 891 1010 2443 882 1063 2444 860 27 2445 847 1064 2446 859 1065 2447 870 507 2448 867 506 2449 869 1066 2450 845 1067 2451 843 509 2452 846 1021 2453 850 1068 2454 869 1066 2455 849 416 2456 907 1069 2457 875 1015 2458 925 328 2459 720 1070 2460 817 1071 2461 716 1072 2462 722 1073 2463 808 1074 2464 718 1040 2465 712 1033 2466 724 1075 2467 725 1034 2468 718 1040 2469 725 1034 2470 722 1073 2471 725 1034 2472 719 1076 2473 722 1073 2474 781 1077 2475 764 942 2476 763 945 2477 714 1078 2478 709 1035 2479 710 1079 2480 729 523 2481 708 1037 2482 716 1036 2483 784 1080 2484 594 1081 2485 705 1082 2486 733 936 2487 739 1083 2488 737 1084 2489 737 1084 2490 740 1085 2491 734 1086 2492 760 1087 2493 748 919 2494 754 1088 2495 761 1042 2496 754 1088 2497 753 1089 2498 713 1090 2499 765 1091 2500 724 1075 2501 775 1092 2502 776 1093 2503 769 1094 2504 732 1095 2505 469 1096 2506 731 1097 2507 779 930 2508 774 1098 2509 780 1099 2510 751 359 2511 757 472 2512 755 470 2513 795 546 2514 796 545 2515 797 483 2516 798 1100 2517 794 1043 2518 799 1045 2519 769 485 2520 472 946 2521 473 549 2522 470 1055 2523 732 1101 2524 733 1053 2525 813 1048 2526 752 921 2527 812 1102 2528 745 1103 2529 759 1104 2530 758 1105 2531 471 1106 2532 775 1107 2533 360 1047 2534 777 1108 2535 773 929 2536 778 931 2537 743 1109 2538 734 1086 2539 740 1085 2540 713 958 2541 763 27 2542 766 27 2543 785 1110 2544 594 1081 2545 786 1111 2546 805 1112 2547 734 482 2548 802 939 2549 735 1046 2550 804 928 2551 803 940 2552 807 1113 2553 811 1114 2554 808 1074 2555 810 949 2556 715 1115 2557 811 1114 2558 790 331 2559 811 1114 2560 795 1050 2561 811 1114 2562 813 1048 2563 795 1050 2564 816 1116 2565 730 567 2566 817 1071 2567 815 960 2568 715 1115 2569 721 948 2570 804 928 2571 816 1116 2572 717 926 2573 819 1117 2574 720 1070 2575 714 1118 2576 751 1119 2577 714 1118 2578 750 1120 2579 754 1121 2580 706 1122 2581 821 1052 2582 595 1123 2583 748 1124 2584 590 1125 2585 590 1125 2586 747 1126 2587 593 1127 2588 706 1122 2589 794 1128 2590 821 1052 2591 741 1129 2592 727 1130 2593 726 1131 2594 471 1106 2595 737 1132 2596 805 1112 2597 738 1133 2598 742 969 2599 739 968 2600 759 1104 2601 757 972 2602 758 1105 2603 833 1134 2604 831 1135 2605 834 1136 2606 826 983 2607 837 980 2608 836 981 2609 832 1137 2610 893 998 2611 831 1135 2612 827 989 2613 833 1134 2614 834 1136 2615 837 980 2616 829 1002 2617 830 1007 2618 842 1138 2619 840 1139 2620 839 1140 2621 848 27 2622 822 1000 2623 847 1064 2624 822 1000 2625 903 27 2626 902 1018 2627 841 1141 2628 855 984 2629 840 1139 2630 854 1142 2631 852 1022 2632 851 1016 2633 829 1002 2634 876 1001 2635 884 1008 2636 881 1009 2637 849 1143 2638 830 1007 2639 855 1144 2640 832 1137 2641 833 1134 2642 907 1145 2643 886 1061 2644 910 1062 2645 869 1146 2646 836 981 2647 837 980 2648 856 1147 2649 872 1148 2650 832 1137 2651 925 997 2652 831 1135 2653 893 998 2654 828 990 2655 855 1144 2656 833 1134 2657 882 1063 2658 927 991 2659 906 1149 2660 862 751 2661 847 1064 2662 871 999 2663 882 1063 2664 884 1008 2665 883 1028 2666 867 1150 2667 825 982 2668 836 981 2669 888 1151 2670 893 998 2671 872 1148 2672 857 138 2673 874 1017 2674 856 410 2675 863 11 2676 861 11 2677 864 11 2678 865 995 2679 864 1152 2680 861 1003 2681 843 509 2682 866 1153 2683 865 1154 2684 883 1028 2685 876 1001 2686 928 1026 2687 881 1009 2688 906 1149 2689 904 1155 2690 878 1005 2691 911 1156 2692 897 1006 2693 851 1157 2694 834 1136 2695 831 1135 2696 923 993 2697 877 1013 2698 894 1004 2699 914 1158 2700 872 1148 2701 874 1159 2702 928 1026 2703 822 1000 2704 902 1018 2705 788 1160 2706 711 1161 2707 723 1032 2708 743 1109 2709 736 912 2710 735 1162 2711 806 1163 2712 810 949 2713 807 1113 2714 710 1079 2715 750 1164 2716 714 1078 2717 806 1163 2718 764 1165 2719 767 618 2720 723 1032 2721 789 1041 2722 788 1160 2723 793 619 2724 798 1100 2725 796 545 2726 768 941 2727 776 1093 2728 762 331 2729 762 1166 2730 781 1167 2731 763 1168 2732 784 952 2733 800 1044 2734 787 953 2735 804 928 2736 772 938 2737 803 940 2738 773 362 2739 805 1112 2740 802 939 2741 767 618 2742 809 947 2743 806 1163 2744 780 1099 2745 767 1169 2746 781 1077 2747 751 1119 2748 814 1031 2749 819 1117 2750 814 1031 2751 813 1048 2752 715 1115 2753 816 1116 2754 818 1030 2755 815 960 2756 716 1072 2757 730 567 2758 729 1170 2759 724 1075 2760 764 1165 2761 719 1076 2762 596 331 2763 785 1110 2764 787 331 2765 776 1171 2766 780 964 2767 781 1167 2768 887 1172 2769 885 996 2770 888 1151 2771 880 987 2772 891 1010 2773 889 1012 2774 879 1023 2775 887 1172 2776 878 1005 2777 868 626 2778 839 1140 2779 867 506 2780 894 1058 2781 924 627 2782 923 502 2783 898 449 2784 922 628 2785 901 1173 2786 834 1136 2787 846 1174 2788 827 989 2789 863 11 2790 859 11 2791 862 11 2792 906 100 2793 873 99 2794 904 101 2795 910 415 2796 908 1175 2797 907 1069 2798 917 33 2799 919 33 2800 918 33 2801 921 1025 2802 918 631 2803 922 328 2804 911 1156 2805 888 1151 2806 914 1158 2807 869 1146 2808 830 1007 2809 849 1143 2810 719 1076 2811 807 1113 2812 722 1073 2813 762 27 2814 239 959 2815 475 27 2816 846 1174 2817 826 983 2818 827 989 2819 931 1176 2820 960 1177 2821 932 1178 2822 970 1179 2823 968 1179 2824 969 1179 2825 961 1180 2826 996 1181 2827 960 1177 2828 967 1182 2829 965 1183 2830 966 1184 2831 968 1185 2832 974 1185 2833 969 1185 2834 986 1186 2835 984 1186 2836 985 1186 2837 936 1187 2838 961 1188 2839 931 1189 2840 956 1190 2841 933 40 2842 930 40 2843 942 11 2844 952 1191 2845 953 1191 2846 984 1192 2847 989 1192 2848 985 1192 2849 954 1193 2850 990 1194 2851 991 1195 2852 992 1196 2853 952 1191 2854 993 1197 2855 983 1198 2856 991 1198 2857 963 1198 2858 958 27 2859 984 27 2860 987 27 2861 955 1199 2862 947 1200 2863 994 1201 2864 951 1202 2865 939 1202 2866 950 1202 2867 949 1203 2868 944 1204 2869 959 1205 2870 977 1206 2871 965 1207 2872 976 1208 2873 948 1209 2874 958 1210 2875 988 1211 2876 953 1212 2877 994 1213 2878 959 1214 2879 947 1200 2880 959 1205 2881 994 1201 2882 996 1181 2883 966 1215 2884 977 1206 2885 929 27 2886 934 27 2887 949 27 2888 937 1216 2889 962 1217 2890 936 1187 2891 974 1218 2892 972 1218 2893 973 1218 2894 981 1219 2895 973 1219 2896 980 1219 2897 973 1220 2898 951 1220 2899 950 1220 2900 971 1221 2901 975 1221 2902 968 1221 2903 965 1222 2904 971 1222 2905 970 1222 2906 942 1223 2907 959 1214 2908 944 1224 2909 945 1225 2910 950 1225 2911 939 1225 2912 951 1226 2913 946 1226 2914 940 1226 2915 989 1227 2916 935 1227 2917 929 1227 2918 988 1228 2919 987 1228 2920 986 1228 2921 990 1194 2922 963 1229 2923 991 1195 2924 989 328 2925 986 328 2926 985 328 2927 991 328 2928 952 328 2929 954 328 2930 994 1213 2931 956 1230 2932 955 1231 2933 995 1232 2934 962 1217 2935 990 1194 2936 979 1233 2937 969 1233 2938 978 1233 2939 957 1234 2940 958 1235 2941 930 1236 2942 976 1237 2943 970 1237 2944 979 1237 2945 969 1238 2946 981 1238 2947 978 1238 2948 941 1239 2949 954 1239 2950 952 1239 2951 967 1182 2952 995 1232 2953 990 1194 2954 943 1240 2955 975 1240 2956 964 1240 2957 943 1241 2958 972 1241 2959 975 1241 2960 943 1242 2961 946 1242 2962 972 1242 2963 956 1190 2964 993 1197 2965 983 1243 2966 989 1244 2967 948 1209 2968 988 1211 2969 954 1193 2970 964 1245 2971 967 1182 2972 980 1246 2973 950 1246 2974 982 1246 2975 933 328 2976 963 328 2977 937 328 2978 931 1247 2979 1019 1248 2980 1020 1249 2981 1029 1250 2982 1027 1250 2983 1030 1250 2984 1055 1251 2985 1020 1249 2986 1019 1248 2987 1024 1252 2988 1026 1253 2989 1025 1254 2990 1027 1255 2991 1033 1255 2992 1034 1255 2993 1045 40 2994 1043 40 2995 1046 40 2996 936 1187 2997 1020 1256 2998 1021 1257 2999 933 40 3000 1015 1258 3001 930 40 3002 1011 1259 3003 1001 33 3004 1012 1260 3005 1043 1261 3006 1048 1261 3007 1016 1261 3008 1013 1262 3009 1049 1263 3010 1026 1253 3011 1011 1259 3012 1051 1264 3013 1052 1265 3014 1050 1266 3015 1042 1266 3016 1022 1266 3017 1043 27 3018 1017 27 3019 1046 27 3020 1014 1267 3021 1006 1268 3022 1007 1269 3023 1010 1270 3024 998 1270 3025 999 1270 3026 1008 1271 3027 1003 1272 3028 997 1273 3029 1036 1274 3030 1024 1275 3031 1025 1276 3032 1007 1269 3033 1017 1277 3034 1014 1267 3035 1053 1278 3036 1012 1279 3037 1018 1280 3038 1018 1281 3039 1006 1268 3040 1053 1282 3041 1055 1251 3042 1025 1276 3043 1054 1283 3044 929 27 3045 1007 27 3046 1008 27 3047 1021 1257 3048 937 1216 3049 936 1187 3050 1033 1284 3051 1031 1284 3052 1034 1284 3053 1040 1285 3054 1032 1285 3055 1033 1285 3056 1010 1286 3057 1032 1286 3058 1009 1286 3059 1030 1287 3060 1034 1287 3061 1023 1287 3062 1030 1288 3063 1024 1288 3064 1029 1288 3065 1001 1289 3066 1018 1280 3067 1012 1279 3068 1004 1290 3069 1009 1290 3070 1041 1290 3071 1010 1291 3072 1005 1291 3073 1031 1291 3074 1048 1292 3075 935 1292 3076 1016 1292 3077 1046 1293 3078 1047 1293 3079 1045 1293 3080 1022 1294 3081 1049 1263 3082 1050 1295 3083 1045 328 3084 1048 328 3085 1044 328 3086 1050 328 3087 1011 328 3088 1052 328 3089 1053 1278 3090 1015 1296 3091 1051 1297 3092 1021 1257 3093 1054 1298 3094 1049 1263 3095 1038 1299 3096 1028 1299 3097 1029 1299 3098 1017 1300 3099 1016 1301 3100 930 1302 3101 1029 1303 3102 1035 1303 3103 1038 1303 3104 1028 1304 3105 1040 1304 3106 1033 1304 3107 1000 328 3108 1013 328 3109 1002 328 3110 1026 1253 3111 1054 1298 3112 1025 1254 3113 1002 1305 3114 1023 1305 3115 1034 1305 3116 1002 1306 3117 1034 1306 3118 1031 1306 3119 1002 1307 3120 1031 1307 3121 1005 1307 3122 1052 1265 3123 1015 1258 3124 1042 1308 3125 1048 1309 3126 1007 1269 3127 929 1310 3128 1023 1311 3129 1013 1262 3130 1026 1253 3131 1009 1312 3132 1039 1312 3133 1041 1312 3134 933 328 3135 1022 328 3136 1042 328 3137 1058 1313 3138 1077 1314 3139 1078 1315 3140 1087 1316 3141 1085 1316 3142 1088 1316 3143 1113 1317 3144 1078 1315 3145 1077 1314 3146 1082 1318 3147 1084 1319 3148 1083 1320 3149 1085 1321 3150 1091 1321 3151 1092 1321 3152 1103 331 3153 1101 331 3154 1104 331 3155 1062 1322 3156 1078 1323 3157 1079 1324 3158 1060 331 3159 1073 1325 3160 1057 331 3161 1069 1326 3162 942 11 3163 1070 1327 3164 1101 1328 3165 1106 1328 3166 1074 1328 3167 1071 1329 3168 1107 1330 3169 1084 1319 3170 1069 1326 3171 1109 1331 3172 1110 1332 3173 1108 1333 3174 1100 1333 3175 1080 1333 3176 1101 27 3177 1075 27 3178 1104 27 3179 1072 1334 3180 1064 1335 3181 1065 1336 3182 1068 1337 3183 939 1337 3184 940 1337 3185 1066 1338 3186 944 1204 3187 938 1339 3188 1094 1340 3189 1082 1341 3190 1083 1342 3191 1065 1336 3192 1075 1343 3193 1072 1334 3194 1111 1344 3195 1070 1345 3196 1076 1346 3197 1076 1347 3198 1064 1335 3199 1111 1348 3200 1113 1317 3201 1083 1342 3202 1112 1349 3203 1056 27 3204 1065 27 3205 1066 27 3206 1079 1324 3207 1063 1350 3208 1062 1322 3209 1091 1351 3210 1089 1351 3211 1092 1351 3212 1098 1352 3213 1090 1352 3214 1091 1352 3215 1068 1353 3216 1090 1353 3217 1067 1353 3218 1088 1354 3219 1092 1354 3220 1081 1354 3221 1088 1355 3222 1082 1355 3223 1087 1355 3224 942 1223 3225 1076 1346 3226 1070 1345 3227 945 1356 3228 1067 1356 3229 1099 1356 3230 1068 1357 3231 946 1357 3232 1089 1357 3233 1106 1358 3234 1061 1358 3235 1074 1358 3236 1104 1228 3237 1105 1228 3238 1103 1228 3239 1080 1359 3240 1107 1330 3241 1108 1360 3242 1103 328 3243 1106 328 3244 1102 328 3245 1108 328 3246 1069 328 3247 1110 328 3248 1111 1344 3249 1073 1361 3250 1109 1362 3251 1079 1324 3252 1112 1363 3253 1107 1330 3254 1096 1364 3255 1086 1364 3256 1087 1364 3257 1075 1365 3258 1074 1366 3259 1057 1367 3260 1087 1368 3261 1093 1368 3262 1096 1368 3263 1086 1369 3264 1098 1369 3265 1091 1369 3266 941 328 3267 1071 328 3268 943 328 3269 1084 1319 3270 1112 1363 3271 1083 1320 3272 943 1240 3273 1081 1240 3274 1092 1240 3275 943 1241 3276 1092 1241 3277 1089 1241 3278 943 1242 3279 1089 1242 3280 946 1242 3281 1110 1332 3282 1073 1325 3283 1100 1370 3284 1106 1371 3285 1065 1336 3286 1056 1372 3287 1081 1373 3288 1071 1329 3289 1084 1319 3290 1067 1374 3291 1097 1374 3292 1099 1374 3293 1060 328 3294 1080 328 3295 1100 328 3296 1058 1375 3297 1127 1376 3298 1059 1375 3299 1137 1377 3300 1135 1377 3301 1136 1377 3302 1128 1378 3303 1163 1379 3304 1127 1376 3305 1134 1380 3306 1132 1381 3307 1133 1382 3308 1135 1383 3309 1141 1383 3310 1136 1383 3311 1153 1384 3312 1151 1384 3313 1152 1384 3314 1062 1322 3315 1128 1385 3316 1058 1386 3317 1123 1387 3318 1060 331 3319 1057 331 3320 1001 33 3321 1119 1388 3322 1120 1388 3323 1151 1389 3324 1156 1389 3325 1152 1389 3326 1121 1390 3327 1157 1391 3328 1158 1392 3329 1159 1393 3330 1119 1388 3331 1160 1394 3332 1150 1395 3333 1158 1395 3334 1130 1395 3335 1125 27 3336 1151 27 3337 1154 27 3338 1122 1396 3339 1114 1397 3340 1161 1398 3341 1118 1399 3342 998 1399 3343 1117 1399 3344 1116 1400 3345 1003 1272 3346 1126 1401 3347 1144 1402 3348 1132 1403 3349 1143 1404 3350 1115 1405 3351 1125 1406 3352 1155 1407 3353 1120 1408 3354 1161 1409 3355 1126 1410 3356 1114 1397 3357 1126 1401 3358 1161 1398 3359 1163 1379 3360 1133 1411 3361 1144 1402 3362 1056 27 3363 934 27 3364 1116 27 3365 1063 1350 3366 1129 1412 3367 1062 1322 3368 1141 1413 3369 1139 1413 3370 1140 1413 3371 1148 1414 3372 1140 1414 3373 1147 1414 3374 1140 1415 3375 1118 1415 3376 1117 1415 3377 1138 1416 3378 1142 1416 3379 1135 1416 3380 1132 1417 3381 1138 1417 3382 1137 1417 3383 1001 1418 3384 1126 1410 3385 1003 1419 3386 1004 1420 3387 1117 1420 3388 998 1420 3389 1118 1421 3390 1005 1421 3391 999 1421 3392 1156 1422 3393 1061 1422 3394 1056 1422 3395 1155 1293 3396 1154 1293 3397 1153 1293 3398 1157 1391 3399 1130 1423 3400 1158 1392 3401 1156 328 3402 1153 328 3403 1152 328 3404 1158 328 3405 1119 328 3406 1121 328 3407 1161 1409 3408 1123 1424 3409 1122 1425 3410 1162 1426 3411 1129 1412 3412 1157 1391 3413 1146 1427 3414 1136 1427 3415 1145 1427 3416 1124 1428 3417 1125 1429 3418 1057 1430 3419 1143 1431 3420 1137 1431 3421 1146 1431 3422 1136 1432 3423 1148 1432 3424 1145 1432 3425 1000 1433 3426 1121 1433 3427 1119 1433 3428 1134 1380 3429 1162 1426 3430 1157 1391 3431 1002 1434 3432 1142 1434 3433 1131 1434 3434 1002 1435 3435 1139 1435 3436 1142 1435 3437 1002 1436 3438 1005 1436 3439 1139 1436 3440 1123 1387 3441 1160 1394 3442 1150 1437 3443 1156 1438 3444 1115 1405 3445 1155 1407 3446 1121 1390 3447 1131 1439 3448 1134 1380 3449 1147 1440 3450 1117 1440 3451 1149 1440 3452 1060 328 3453 1130 328 3454 1063 328 3455 34 5 3456 33 0 3457 22 4 3458 75 7 3459 74 1441 3460 93 8 3461 112 15 3462 104 242 3463 44 16 3464 39 18 3465 38 1442 3466 117 19 3467 9 21 3468 101 50 3469 66 22 3470 65 24 3471 64 1443 3472 71 25 3473 243 27 3474 116 27 3475 63 27 3476 64 36 3477 65 314 3478 94 37 3479 240 47 3480 60 1444 3481 62 48 3482 101 50 3483 9 21 3484 13 51 3485 9 21 3486 108 257 3487 107 66 3488 160 90 3489 159 294 3490 158 91 3491 229 93 3492 228 192 3493 207 94 3494 201 96 3495 202 142 3496 211 97 3497 175 99 3498 152 204 3499 151 100 3500 201 102 3501 181 146 3502 182 103 3503 129 105 3504 128 89 3505 127 88 3506 229 107 3507 193 127 3508 194 108 3509 187 112 3510 209 287 3511 227 113 3512 173 115 3513 149 197 3514 124 116 3515 196 121 3516 179 130 3517 180 122 3518 132 124 3519 131 118 3520 186 125 3521 216 131 3522 215 138 3523 214 132 3524 177 134 3525 156 284 3526 153 135 3527 176 137 3528 126 1445 3529 215 138 3530 204 139 3531 205 27 3532 218 27 3533 200 141 3534 203 322 3535 202 142 3536 155 143 3537 147 202 3538 148 144 3539 181 146 3540 180 122 3541 179 130 3542 141 147 3543 142 1446 3544 130 106 3545 222 150 3546 230 149 3547 204 139 3548 110 153 3549 111 259 3550 106 154 3551 15 155 3552 3 304 3553 4 156 3554 1 158 3555 12 1447 3556 8 159 3557 47 161 3558 49 237 3559 48 162 3560 10 164 3561 100 210 3562 82 165 3563 53 167 3564 45 226 3565 44 163 3566 86 168 3567 79 56 3568 92 169 3569 62 48 3570 63 1448 3571 116 171 3572 93 172 3573 74 33 3574 83 57 3575 232 27 3576 115 27 3577 75 67 3578 94 37 3579 26 253 3580 27 173 3581 82 60 3582 87 238 3583 89 174 3584 123 175 3585 67 247 3586 61 176 3587 105 178 3588 104 242 3589 85 179 3590 85 179 3591 104 242 3592 112 15 3593 113 182 3594 86 270 3595 84 181 3596 45 17 3597 46 263 3598 113 182 3599 25 183 3600 29 274 3601 242 184 3602 79 186 3603 86 270 3604 234 187 3605 93 8 3606 89 83 3607 91 82 3608 199 188 3609 198 193 3610 197 189 3611 225 191 3612 226 320 3613 228 192 3614 213 133 3615 214 132 3616 198 193 3617 188 194 3618 181 146 3619 201 102 3620 221 11 3621 222 11 3622 217 11 3623 185 151 3624 192 128 3625 193 127 3626 162 27 3627 150 27 3628 149 197 3629 172 199 3630 170 319 3631 169 200 3632 147 202 3633 146 884 3634 145 203 3635 152 204 3636 172 199 3637 171 201 3638 209 205 3639 210 326 3640 177 134 3641 12 206 3642 110 153 3643 109 207 3644 14 209 3645 99 254 3646 100 210 3647 4 156 3648 5 227 3649 16 211 3650 10 164 3651 15 155 3652 17 157 3653 17 157 3654 16 211 3655 11 212 3656 73 213 3657 59 315 3658 56 43 3659 6 214 3660 12 1447 3661 1 158 3662 21 216 3663 20 811 3664 0 160 3665 76 217 3666 78 251 3667 119 218 3668 25 32 3669 30 30 3670 31 220 3671 29 221 3672 31 220 3673 32 222 3674 52 224 3675 51 10 3676 40 14 3677 53 167 3678 52 224 3679 46 225 3680 5 227 3681 58 821 3682 57 228 3683 67 229 3684 69 248 3685 68 230 3686 24 232 3687 235 1449 3688 236 233 3689 71 25 3690 64 1443 3691 66 235 3692 43 35 3693 50 34 3694 49 237 3695 87 238 3696 85 310 3697 88 239 3698 90 240 3699 84 832 3700 86 168 3701 61 176 3702 60 1444 3703 240 47 3704 237 185 3705 235 1450 3706 24 241 3707 105 178 3708 47 1451 3709 44 16 3710 37 243 3711 36 1452 3712 51 244 3713 238 246 3714 97 252 3715 67 247 3716 69 248 3717 67 229 3718 65 24 3719 35 249 3720 27 305 3721 26 223 3722 5 63 3723 74 62 3724 55 27 3725 77 250 3726 231 1453 3727 119 218 3728 97 252 3729 29 274 3730 26 253 3731 27 173 3732 28 1454 3733 96 23 3734 99 254 3735 102 52 3736 103 255 3737 102 52 3738 13 51 3739 7 256 3740 82 165 3741 100 210 3742 103 255 3743 103 255 3744 7 256 3745 105 178 3746 108 257 3747 28 1454 3748 22 258 3749 107 66 3750 106 154 3751 7 256 3752 96 23 3753 28 1454 3754 108 257 3755 111 259 3756 110 153 3757 12 206 3758 43 261 3759 111 259 3760 6 260 3761 46 263 3762 120 265 3763 233 264 3764 120 265 3765 46 263 3766 40 266 3767 114 267 3768 40 266 3769 39 268 3770 233 264 3771 234 187 3772 86 270 3773 33 271 3774 30 275 3775 19 272 3776 238 246 3777 242 184 3778 29 274 3779 30 275 3780 33 271 3781 34 75 3782 51 244 3783 52 79 3784 49 78 3785 135 276 3786 134 279 3787 133 277 3788 128 89 3789 137 84 3790 139 86 3791 134 279 3792 174 290 3793 195 114 3794 129 105 3795 130 106 3796 135 276 3797 139 86 3798 140 85 3799 131 118 3800 144 280 3801 143 283 3802 142 281 3803 150 27 3804 125 27 3805 124 116 3806 124 116 3807 125 27 3808 205 27 3809 143 283 3810 160 90 3811 157 92 3812 156 284 3813 155 143 3814 154 145 3815 131 118 3816 173 115 3817 178 117 3818 183 126 3819 206 298 3820 151 285 3821 157 286 3822 158 289 3823 134 279 3824 209 287 3825 187 112 3826 188 194 3827 171 288 3828 169 292 3829 138 87 3830 158 289 3831 176 302 3832 174 290 3833 227 113 3834 153 300 3835 133 277 3836 130 106 3837 142 1446 3838 157 286 3839 184 196 3840 193 127 3841 229 107 3842 164 120 3843 161 198 3844 149 197 3845 184 196 3846 183 126 3847 186 125 3848 169 292 3849 141 147 3850 127 88 3851 190 293 3852 187 112 3853 195 114 3854 159 294 3855 126 1445 3856 176 137 3857 165 33 3858 164 33 3859 163 33 3860 167 111 3861 168 328 3862 166 295 3863 145 203 3864 146 884 3865 168 296 3866 185 151 3867 186 125 3868 178 117 3869 183 126 3870 184 196 3871 208 291 3872 180 122 3873 189 318 3874 213 299 3875 153 300 3876 154 1455 3877 136 278 3878 225 109 3879 194 108 3880 179 130 3881 216 301 3882 190 293 3883 174 290 3884 230 149 3885 178 117 3886 124 116 3887 80 303 3888 83 1456 3889 3 304 3890 35 249 3891 34 5 3892 28 6 3893 98 306 3894 101 50 3895 102 52 3896 2 215 3897 41 1457 3898 42 307 3899 98 306 3900 11 212 3901 56 308 3902 15 155 3903 10 164 3904 81 166 3905 85 310 3906 84 832 3907 90 240 3908 60 41 3909 61 231 3910 68 230 3911 54 311 3912 68 317 3913 73 312 3914 76 55 3915 75 11 3916 92 169 3917 96 23 3918 66 22 3919 64 36 3920 65 314 3921 67 247 3922 97 252 3923 59 309 3924 66 22 3925 101 50 3926 72 236 3927 66 235 3928 59 315 3929 43 261 3930 47 1451 3931 106 154 3932 106 154 3933 47 1451 3934 105 178 3935 108 257 3936 109 207 3937 110 153 3938 8 208 3939 109 207 3940 22 258 3941 16 211 3942 57 228 3943 56 308 3944 121 40 3945 231 1453 3946 77 250 3947 68 317 3948 69 71 3949 72 70 3950 189 318 3951 188 194 3952 187 112 3953 182 103 3954 194 108 3955 193 127 3956 181 146 3957 188 194 3958 189 318 3959 170 319 3960 144 280 3961 141 282 3962 196 190 3963 197 189 3964 226 320 3965 200 141 3966 223 906 3967 224 321 3968 136 278 3969 154 1455 3970 148 323 3971 165 33 3972 162 33 3973 161 33 3974 208 95 3975 207 94 3976 175 324 3977 212 98 3978 211 97 3979 210 326 3980 219 11 3981 222 11 3982 221 11 3983 223 148 3984 219 152 3985 220 327 3986 213 299 3987 189 318 3988 190 293 3989 171 288 3990 139 86 3991 132 124 3992 11 212 3993 98 306 3994 99 254 3995 148 323 3996 145 110 3997 128 89 3998 278 333 3999 272 612 4000 266 4 4001 337 334 4002 318 1458 4003 319 335 4004 356 341 4005 289 493 4006 288 342 4007 117 344 4008 282 1459 4009 283 345 4010 253 347 4011 340 562 4012 310 348 4013 315 350 4014 308 544 4015 309 351 4016 307 27 4017 358 27 4018 475 27 4019 308 360 4020 339 940 4021 338 361 4022 306 368 4023 304 1460 4024 472 369 4025 257 371 4026 253 347 4027 345 349 4028 253 347 4029 257 371 4030 351 385 4031 395 410 4032 396 601 4033 397 411 4034 444 413 4035 465 501 4036 466 414 4037 448 143 4038 439 202 4039 438 144 4040 388 416 4041 389 511 4042 412 417 4043 438 418 4044 437 456 4045 419 419 4046 366 421 4047 367 454 4048 364 409 4049 466 422 4050 462 609 4051 431 423 4052 464 427 4053 446 595 4054 424 428 4055 410 430 4056 415 589 4057 361 431 4058 433 436 4059 436 1461 4060 417 437 4061 369 439 4062 420 590 4063 423 440 4064 451 443 4065 452 294 4066 453 444 4067 390 446 4068 393 588 4069 414 447 4070 452 294 4071 363 27 4072 413 27 4073 455 27 4074 442 27 4075 441 432 4076 439 202 4077 440 1173 4078 437 449 4079 385 450 4080 384 510 4081 392 451 4082 418 420 4083 419 419 4084 416 438 4085 378 453 4086 364 409 4087 367 454 4088 459 435 4089 454 448 4090 441 432 4091 354 461 4092 351 385 4093 350 462 4094 259 464 4095 261 518 4096 248 465 4097 245 467 4098 244 524 4099 252 468 4100 291 470 4101 288 475 4102 292 471 4103 326 473 4104 344 515 4105 254 474 4106 288 475 4107 289 1089 4108 297 476 4109 330 477 4110 335 1462 4111 336 478 4112 358 479 4113 307 1463 4114 306 368 4115 337 480 4116 326 380 4117 327 377 4118 232 27 4119 320 27 4120 319 387 4121 338 361 4122 339 940 4123 271 481 4124 333 483 4125 331 546 4126 326 380 4127 360 484 4128 473 549 4129 305 485 4130 329 487 4131 348 343 4132 349 488 4133 329 487 4134 328 491 4135 356 341 4136 357 490 4137 356 341 4138 328 491 4139 289 493 4140 356 341 4141 357 490 4142 474 495 4143 273 561 4144 269 496 4145 234 40 4146 330 492 4147 323 40 4148 336 336 4149 335 401 4150 333 403 4151 434 498 4152 435 503 4153 436 499 4154 465 501 4155 463 627 4156 462 502 4157 435 503 4158 451 443 4159 450 445 4160 425 504 4161 449 1464 4162 438 418 4163 458 33 4164 455 33 4165 454 33 4166 430 424 4167 429 442 4168 422 459 4169 386 432 4170 387 27 4171 399 27 4172 406 506 4173 407 626 4174 409 507 4175 382 509 4176 383 322 4177 384 510 4178 408 508 4179 409 507 4180 389 511 4181 414 447 4182 447 630 4183 446 512 4184 256 513 4185 252 624 4186 353 514 4187 344 515 4188 343 565 4189 258 516 4190 260 517 4191 249 534 4192 248 465 4193 254 474 4194 258 516 4195 261 518 4196 255 519 4197 260 517 4198 261 518 4199 317 520 4200 299 367 4201 300 364 4202 250 522 4203 246 614 4204 245 467 4205 265 523 4206 252 468 4207 244 524 4208 320 526 4209 232 1465 4210 119 527 4211 269 357 4212 273 530 4213 275 529 4214 273 530 4215 270 558 4216 276 531 4217 296 532 4218 290 533 4219 284 340 4220 297 476 4221 289 1089 4222 290 533 4223 249 534 4224 260 517 4225 301 535 4226 312 537 4227 313 557 4228 311 538 4229 469 540 4230 468 1466 4231 268 541 4232 315 350 4233 316 623 4234 310 543 4235 287 359 4236 291 470 4237 293 472 4238 332 545 4239 329 619 4240 331 546 4241 334 547 4242 335 1462 4243 330 477 4244 472 369 4245 304 1460 4246 305 485 4247 268 550 4248 468 1467 4249 470 497 4250 349 488 4251 348 343 4252 288 342 4253 295 552 4254 280 1452 4255 281 553 4256 471 555 4257 360 484 4258 311 486 4259 313 557 4260 314 352 4261 309 351 4262 270 558 4263 271 1468 4264 279 559 4265 249 381 4266 302 27 4267 299 27 4268 119 527 4269 231 1469 4270 321 560 4271 341 556 4272 338 361 4273 270 482 4274 271 481 4275 339 940 4276 340 562 4277 347 564 4278 346 372 4279 343 565 4280 251 566 4281 257 371 4282 346 372 4283 326 473 4284 331 489 4285 347 564 4286 349 488 4287 251 566 4288 347 564 4289 352 386 4290 353 514 4291 266 567 4292 351 385 4293 257 371 4294 251 566 4295 352 386 4296 272 563 4297 340 562 4298 355 463 4299 250 569 4300 256 513 4301 287 568 4302 286 1470 4303 250 569 4304 233 570 4305 120 571 4306 290 494 4307 120 571 4308 114 574 4309 284 572 4310 283 573 4311 284 572 4312 114 574 4313 233 570 4314 357 490 4315 330 492 4316 263 576 4317 274 579 4318 277 577 4319 471 555 4320 341 556 4321 273 561 4322 274 579 4323 275 393 4324 278 395 4325 293 397 4326 296 399 4327 295 552 4328 372 580 4329 373 607 4330 370 581 4331 365 408 4332 375 407 4333 376 405 4334 371 582 4335 370 581 4336 432 429 4337 366 421 4338 373 607 4339 372 580 4340 368 433 4341 377 406 4342 376 405 4343 379 584 4344 380 587 4345 381 585 4346 361 431 4347 362 27 4348 387 27 4349 442 27 4350 362 27 4351 361 431 4352 394 412 4353 397 411 4354 380 587 4355 391 452 4356 392 451 4357 393 588 4358 368 433 4359 423 440 4360 415 589 4361 420 590 4362 369 439 4363 388 591 4364 394 593 4365 372 580 4366 371 582 4367 446 595 4368 449 1464 4369 425 504 4370 408 596 4371 376 405 4372 375 407 4373 395 594 4374 371 582 4375 411 583 4376 370 581 4377 390 606 4378 464 427 4379 367 454 4380 372 580 4381 394 593 4382 466 422 4383 430 424 4384 421 505 4385 401 435 4386 410 430 4387 386 432 4388 421 505 4389 422 459 4390 423 440 4391 406 597 4392 375 407 4393 364 409 4394 427 600 4395 411 583 4396 432 429 4397 413 27 4398 363 27 4399 396 601 4400 400 11 4401 401 11 4402 402 11 4403 404 426 4404 400 434 4405 403 602 4406 382 509 4407 404 1154 4408 405 603 4409 422 459 4410 467 458 4411 415 589 4412 420 590 4413 443 592 4414 445 599 4415 417 437 4416 436 1461 4417 450 604 4418 390 606 4419 370 581 4420 373 607 4421 462 609 4422 433 436 4423 416 438 4424 453 610 4425 413 598 4426 411 583 4427 467 458 4428 441 432 4429 361 431 4430 324 303 4431 259 464 4432 247 466 4433 279 559 4434 271 1468 4435 272 612 4436 346 372 4437 345 349 4438 342 613 4439 246 614 4440 250 522 4441 286 615 4442 300 617 4443 255 519 4444 342 613 4445 259 464 4446 324 303 4447 325 166 4448 329 619 4449 332 545 4450 334 547 4451 304 363 4452 298 40 4453 312 537 4454 317 620 4455 312 625 4456 298 621 4457 320 374 4458 323 376 4459 336 478 4460 340 562 4461 339 940 4462 308 360 4463 309 362 4464 338 361 4465 341 556 4466 345 349 4467 310 348 4468 303 618 4469 316 623 4470 317 520 4471 303 521 4472 287 568 4473 355 463 4474 350 462 4475 350 462 4476 251 566 4477 349 488 4478 352 386 4479 351 385 4480 354 461 4481 252 624 4482 265 1170 4483 266 567 4484 260 517 4485 255 519 4486 300 617 4487 321 560 4488 231 1469 4489 121 40 4490 316 389 4491 313 391 4492 312 625 4493 426 605 4494 427 600 4495 424 428 4496 430 424 4497 431 423 4498 419 419 4499 418 420 4500 417 437 4501 426 605 4502 378 586 4503 381 585 4504 407 626 4505 463 627 4506 434 498 4507 433 500 4508 437 449 4509 440 1173 4510 461 628 4511 373 607 4512 366 421 4513 385 629 4514 402 11 4515 401 11 4516 398 11 4517 412 99 4518 444 413 4519 445 100 4520 447 630 4521 448 143 4522 449 415 4523 458 33 4524 459 33 4525 456 33 4526 460 457 4527 461 328 4528 457 631 4529 450 604 4530 453 610 4531 427 600 4532 369 439 4533 376 405 4534 408 596 4535 343 565 4536 342 613 4537 255 519 4538 385 629 4539 366 421 4540 365 408 4541 510 636 4542 504 894 4543 498 635 4544 569 637 4545 550 639 4546 551 638 4547 588 643 4548 521 782 4549 520 644 4550 592 646 4551 514 1471 4552 515 647 4553 485 649 4554 572 845 4555 542 22 4556 547 651 4557 540 829 4558 541 652 4559 539 27 4560 116 27 4561 243 27 4562 540 662 4563 571 1472 4564 570 663 4565 538 48 4566 536 1444 4567 240 671 4568 489 672 4569 485 649 4570 577 650 4571 485 649 4572 489 672 4573 583 687 4574 631 712 4575 632 883 4576 633 90 4577 680 94 4578 701 192 4579 702 93 4580 684 97 4581 675 142 4582 674 96 4583 624 100 4584 625 798 4585 648 99 4586 674 714 4587 673 748 4588 655 715 4589 602 717 4590 603 746 4591 600 711 4592 702 718 4593 698 890 4594 667 719 4595 700 723 4596 682 877 4597 660 724 4598 646 726 4599 651 871 4600 597 727 4601 669 732 4602 672 1473 4603 653 733 4604 605 735 4605 656 872 4606 659 736 4607 687 132 4608 688 138 4609 689 131 4610 626 135 4611 629 870 4612 650 740 4613 688 138 4614 599 1445 4615 649 741 4616 691 27 4617 678 27 4618 677 742 4619 675 142 4620 676 322 4621 673 141 4622 621 744 4623 620 797 4624 628 143 4625 654 716 4626 655 715 4627 652 734 4628 614 745 4629 600 711 4630 603 746 4631 695 751 4632 690 743 4633 677 742 4634 586 754 4635 583 687 4636 582 755 4637 491 757 4638 493 805 4639 480 758 4640 477 760 4641 476 810 4642 484 761 4643 523 763 4644 520 768 4645 524 764 4646 558 765 4647 576 802 4648 486 766 4649 520 768 4650 521 1474 4651 529 769 4652 562 770 4653 567 170 4654 568 771 4655 116 171 4656 539 1448 4657 538 48 4658 569 172 4659 558 681 4660 559 678 4661 705 27 4662 552 27 4663 551 689 4664 570 663 4665 571 1472 4666 503 772 4667 565 174 4668 563 830 4669 558 681 4670 123 774 4671 241 177 4672 537 176 4673 561 776 4674 580 645 4675 581 777 4676 561 776 4677 560 780 4678 588 643 4679 589 779 4680 588 643 4681 560 780 4682 521 782 4683 588 643 4684 589 779 4685 242 784 4686 505 844 4687 501 785 4688 707 787 4689 562 781 4690 555 788 4691 567 703 4692 565 705 4693 569 637 4694 670 789 4695 671 792 4696 672 790 4697 701 192 4698 699 320 4699 698 191 4700 671 792 4701 687 132 4702 686 739 4703 661 793 4704 685 1475 4705 674 714 4706 694 11 4707 691 11 4708 690 11 4709 666 720 4710 665 738 4711 658 752 4712 622 728 4713 623 27 4714 635 27 4715 642 200 4716 643 905 4717 645 199 4718 618 796 4719 619 884 4720 620 797 4721 644 201 4722 645 199 4723 625 798 4724 650 740 4725 683 326 4726 682 799 4727 488 800 4728 484 903 4729 585 801 4730 576 802 4731 575 848 4732 490 803 4733 492 804 4734 481 819 4735 480 758 4736 486 766 4737 490 803 4738 493 805 4739 487 806 4740 492 804 4741 493 805 4742 549 807 4743 531 670 4744 532 667 4745 482 809 4746 478 896 4747 477 760 4748 497 216 4749 484 761 4750 476 810 4751 552 812 4752 705 1476 4753 594 813 4754 501 658 4755 505 816 4756 507 815 4757 505 816 4758 502 841 4759 508 817 4760 528 224 4761 522 818 4762 516 14 4763 529 769 4764 521 1474 4765 522 818 4766 481 819 4767 492 804 4768 533 820 4769 544 822 4770 545 840 4771 543 823 4772 236 825 4773 235 1449 4774 500 826 4775 547 651 4776 548 902 4777 542 828 4778 519 35 4779 523 763 4780 525 237 4781 564 239 4782 561 310 4783 563 830 4784 566 831 4785 567 170 4786 562 770 4787 240 671 4788 536 1444 4789 537 176 4790 500 833 4791 235 1450 4792 237 786 4793 581 777 4794 580 645 4795 520 644 4796 527 835 4797 512 1477 4798 513 836 4799 238 838 4800 123 774 4801 543 775 4802 545 840 4803 546 653 4804 541 652 4805 502 841 4806 503 1478 4807 511 842 4808 481 684 4809 534 27 4810 531 27 4811 594 813 4812 704 1479 4813 553 843 4814 573 839 4815 570 663 4816 502 773 4817 503 772 4818 571 1472 4819 572 845 4820 579 847 4821 578 673 4822 575 848 4823 483 849 4824 489 672 4825 578 673 4826 558 765 4827 563 778 4828 579 847 4829 581 777 4830 483 849 4831 579 847 4832 584 688 4833 585 801 4834 498 258 4835 583 687 4836 489 672 4837 483 849 4838 584 688 4839 504 846 4840 572 845 4841 587 756 4842 482 851 4843 488 800 4844 519 850 4845 518 1480 4846 482 851 4847 706 852 4848 595 853 4849 522 783 4850 595 853 4851 590 856 4852 516 854 4853 515 855 4854 516 854 4855 590 856 4856 706 852 4857 589 779 4858 562 781 4859 495 858 4860 506 861 4861 509 859 4862 238 838 4863 573 839 4864 505 844 4865 506 861 4866 507 695 4867 510 697 4868 525 699 4869 528 701 4870 527 835 4871 608 862 4872 609 888 4873 606 863 4874 601 710 4875 611 709 4876 612 707 4877 607 864 4878 606 863 4879 668 725 4880 602 717 4881 609 888 4882 608 862 4883 604 729 4884 613 708 4885 612 707 4886 615 866 4887 616 869 4888 617 867 4889 597 727 4890 598 27 4891 623 27 4892 678 27 4893 598 27 4894 597 727 4895 630 713 4896 633 90 4897 616 869 4898 627 145 4899 628 143 4900 629 870 4901 604 729 4902 659 736 4903 651 871 4904 656 872 4905 605 735 4906 624 873 4907 630 875 4908 608 862 4909 607 864 4910 682 877 4911 685 1475 4912 661 793 4913 644 878 4914 612 707 4915 611 709 4916 631 876 4917 607 864 4918 647 865 4919 606 863 4920 626 887 4921 700 723 4922 603 746 4923 608 862 4924 630 875 4925 702 718 4926 666 720 4927 657 794 4928 637 731 4929 646 726 4930 622 728 4931 657 794 4932 658 752 4933 659 736 4934 642 879 4935 611 709 4936 600 711 4937 663 882 4938 647 865 4939 668 725 4940 649 741 4941 599 1445 4942 632 883 4943 636 33 4944 637 33 4945 638 33 4946 640 722 4947 636 730 4948 639 295 4949 618 796 4950 640 297 4951 641 296 4952 658 752 4953 703 750 4954 651 871 4955 656 872 4956 679 874 4957 681 881 4958 653 733 4959 672 1473 4960 686 885 4961 626 887 4962 606 863 4963 609 888 4964 698 890 4965 669 732 4966 652 734 4967 689 891 4968 649 880 4969 647 865 4970 703 750 4971 677 742 4972 597 727 4973 556 892 4974 491 757 4975 479 759 4976 511 842 4977 503 1478 4978 504 894 4979 578 673 4980 577 650 4981 574 895 4982 478 896 4983 482 809 4984 518 897 4985 532 899 4986 487 806 4987 574 895 4988 491 757 4989 556 892 4990 557 767 4991 561 310 4992 564 239 4993 566 831 4994 536 665 4995 530 666 4996 544 822 4997 549 900 4998 544 904 4999 530 901 5000 552 675 5001 555 677 5002 568 771 5003 572 845 5004 571 1472 5005 540 662 5006 541 314 5007 570 663 5008 573 839 5009 577 650 5010 542 22 5011 535 309 5012 548 902 5013 549 807 5014 535 808 5015 519 850 5016 587 756 5017 582 755 5018 582 755 5019 483 849 5020 581 777 5021 584 688 5022 583 687 5023 586 754 5024 484 903 5025 497 316 5026 498 258 5027 492 804 5028 487 806 5029 532 899 5030 553 843 5031 704 1479 5032 596 331 5033 548 691 5034 545 693 5035 544 904 5036 662 886 5037 663 882 5038 660 724 5039 666 720 5040 667 719 5041 655 715 5042 654 716 5043 653 733 5044 662 886 5045 614 868 5046 617 867 5047 643 905 5048 699 320 5049 670 789 5050 669 791 5051 673 141 5052 676 322 5053 697 321 5054 609 888 5055 602 717 5056 621 907 5057 638 33 5058 637 33 5059 634 33 5060 648 324 5061 680 94 5062 681 95 5063 683 326 5064 684 97 5065 685 98 5066 694 11 5067 695 11 5068 692 11 5069 696 749 5070 697 328 5071 693 327 5072 686 885 5073 689 891 5074 663 882 5075 605 735 5076 612 707 5077 644 878 5078 575 848 5079 574 895 5080 487 806 5081 621 907 5082 602 717 5083 601 710 5084 742 911 5085 741 632 5086 730 910 5087 783 913 5088 782 913 5089 801 914 5090 820 920 5091 812 1102 5092 752 921 5093 747 923 5094 746 1481 5095 592 924 5096 717 926 5097 809 947 5098 774 927 5099 773 929 5100 772 1482 5101 779 930 5102 475 27 5103 358 27 5104 771 27 5105 772 938 5106 773 362 5107 802 939 5108 472 946 5109 768 1460 5110 770 368 5111 809 947 5112 717 926 5113 721 948 5114 717 926 5115 816 1116 5116 815 960 5117 858 411 5118 857 138 5119 856 410 5120 927 985 5121 926 1059 5122 905 798 5123 899 744 5124 900 797 5125 909 143 5126 873 417 5127 850 1068 5128 849 416 5129 899 986 5130 879 1023 5131 880 987 5132 827 989 5133 826 983 5134 825 982 5135 927 991 5136 891 1010 5137 892 992 5138 885 996 5139 907 1145 5140 925 997 5141 871 999 5142 847 1064 5143 822 1000 5144 894 1004 5145 877 1013 5146 878 1005 5147 830 1007 5148 829 1002 5149 884 1008 5150 914 444 5151 913 294 5152 912 443 5153 875 1015 5154 854 1142 5155 851 1016 5156 874 1017 5157 824 1483 5158 913 294 5159 902 1018 5160 903 27 5161 916 27 5162 898 449 5163 901 1173 5164 900 797 5165 853 1020 5166 845 1067 5167 846 1021 5168 879 1023 5169 878 1005 5170 877 1013 5171 839 1024 5172 840 1484 5173 828 990 5174 920 1027 5175 928 1026 5176 902 1018 5177 818 1030 5178 819 1117 5179 814 1031 5180 723 1032 5181 711 1161 5182 712 1033 5183 709 1035 5184 720 1485 5185 716 1036 5186 755 470 5187 757 472 5188 756 1038 5189 718 1040 5190 808 1074 5191 790 331 5192 761 1042 5193 753 1089 5194 752 1039 5195 794 1043 5196 787 953 5197 800 1044 5198 770 368 5199 771 1463 5200 358 479 5201 801 480 5202 782 11 5203 791 954 5204 705 27 5205 591 27 5206 783 961 5207 802 939 5208 734 482 5209 735 1046 5210 790 957 5211 795 546 5212 797 483 5213 360 1047 5214 775 1107 5215 769 485 5216 813 1048 5217 812 1102 5218 793 1049 5219 793 1049 5220 812 1102 5221 820 920 5222 821 1052 5223 794 1128 5224 792 1051 5225 753 922 5226 754 1121 5227 821 1052 5228 733 1053 5229 737 1132 5230 474 1054 5231 787 331 5232 794 1128 5233 707 331 5234 800 915 5235 801 914 5236 797 977 5237 897 1056 5238 896 1060 5239 895 1057 5240 923 502 5241 924 627 5242 926 1059 5243 911 1014 5244 912 443 5245 896 1060 5246 886 1061 5247 879 1023 5248 899 986 5249 919 33 5250 920 33 5251 915 33 5252 883 1028 5253 890 1011 5254 891 1010 5255 860 27 5256 848 27 5257 847 1064 5258 870 507 5259 868 626 5260 867 506 5261 845 1067 5262 844 322 5263 843 509 5264 850 1068 5265 870 507 5266 869 1066 5267 907 1069 5268 908 1175 5269 875 1015 5270 720 1070 5271 818 1030 5272 817 1071 5273 722 1073 5274 807 1113 5275 808 1074 5276 712 1033 5277 713 1090 5278 724 1075 5279 718 1040 5280 723 1032 5281 725 1034 5282 725 1034 5283 724 1075 5284 719 1076 5285 781 1077 5286 767 1169 5287 764 942 5288 714 1078 5289 720 1485 5290 709 1035 5291 729 523 5292 728 525 5293 708 1037 5294 784 1080 5295 786 1111 5296 594 1081 5297 733 936 5298 738 934 5299 739 1083 5300 737 1084 5301 739 1083 5302 740 1085 5303 760 1087 5304 759 916 5305 748 919 5306 761 1042 5307 760 1087 5308 754 1088 5309 713 1090 5310 766 536 5311 765 1091 5312 775 1092 5313 777 1108 5314 776 1093 5315 732 1095 5316 468 1466 5317 469 1096 5318 779 930 5319 772 1482 5320 774 1098 5321 751 359 5322 758 937 5323 757 472 5324 795 546 5325 793 619 5326 796 545 5327 798 1100 5328 792 548 5329 794 1043 5330 769 485 5331 768 1460 5332 472 946 5333 470 1055 5334 468 1467 5335 732 1101 5336 813 1048 5337 755 1486 5338 752 921 5339 745 1103 5340 744 1487 5341 759 1104 5342 471 1106 5343 805 1112 5344 775 1107 5345 777 1108 5346 775 1092 5347 773 929 5348 743 1109 5349 735 1162 5350 734 1086 5351 713 958 5352 782 382 5353 763 27 5354 785 1110 5355 704 1488 5356 594 1081 5357 805 1112 5358 737 1132 5359 734 482 5360 735 1046 5361 736 1489 5362 804 928 5363 807 1113 5364 810 949 5365 811 1114 5366 810 949 5367 721 948 5368 715 1115 5369 790 331 5370 808 1074 5371 811 1114 5372 811 1114 5373 715 1115 5374 813 1048 5375 816 1116 5376 736 1489 5377 730 567 5378 815 960 5379 814 1031 5380 715 1115 5381 804 928 5382 736 1489 5383 816 1116 5384 819 1117 5385 818 1030 5386 720 1070 5387 751 1119 5388 819 1117 5389 714 1118 5390 754 1121 5391 595 1123 5392 706 1122 5393 595 1123 5394 754 1121 5395 748 1124 5396 590 1125 5397 748 1124 5398 747 1126 5399 706 1122 5400 707 331 5401 794 1128 5402 741 1129 5403 738 1133 5404 727 1130 5405 471 1106 5406 474 1054 5407 737 1132 5408 738 1133 5409 741 1129 5410 742 969 5411 759 1104 5412 760 973 5413 757 972 5414 833 1134 5415 832 1137 5416 831 1135 5417 826 983 5418 835 978 5419 837 980 5420 832 1137 5421 872 1148 5422 893 998 5423 827 989 5424 828 990 5425 833 1134 5426 837 980 5427 838 979 5428 829 1002 5429 842 1138 5430 841 1141 5431 840 1139 5432 848 27 5433 823 27 5434 822 1000 5435 822 1000 5436 823 27 5437 903 27 5438 841 1141 5439 858 411 5440 855 984 5441 854 1142 5442 853 1020 5443 852 1022 5444 829 1002 5445 871 999 5446 876 1001 5447 881 1009 5448 904 1155 5449 849 1143 5450 855 1144 5451 856 1147 5452 832 1137 5453 907 1145 5454 885 996 5455 886 1061 5456 869 1146 5457 867 1150 5458 836 981 5459 856 1147 5460 874 1159 5461 872 1148 5462 925 997 5463 851 1157 5464 831 1135 5465 828 990 5466 840 1484 5467 855 1144 5468 882 1063 5469 891 1010 5470 927 991 5471 862 751 5472 859 1065 5473 847 1064 5474 882 1063 5475 881 1009 5476 884 1008 5477 867 1150 5478 839 1024 5479 825 982 5480 888 1151 5481 885 996 5482 893 998 5483 857 138 5484 824 1483 5485 874 1017 5486 863 11 5487 862 11 5488 861 11 5489 865 995 5490 866 328 5491 864 1152 5492 843 509 5493 844 322 5494 866 1153 5495 883 1028 5496 884 1008 5497 876 1001 5498 881 1009 5499 882 1063 5500 906 1149 5501 878 1005 5502 887 1172 5503 911 1156 5504 851 1157 5505 852 1490 5506 834 1136 5507 923 993 5508 892 992 5509 877 1013 5510 914 1158 5511 888 1151 5512 872 1148 5513 928 1026 5514 876 1001 5515 822 1000 5516 788 1160 5517 791 1491 5518 711 1161 5519 743 1109 5520 742 911 5521 736 912 5522 806 1163 5523 809 947 5524 810 949 5525 710 1079 5526 749 1492 5527 750 1164 5528 806 1163 5529 719 1076 5530 764 1165 5531 723 1032 5532 718 1040 5533 789 1041 5534 793 619 5535 792 548 5536 798 1100 5537 768 941 5538 769 1094 5539 776 1093 5540 762 1166 5541 776 1171 5542 781 1167 5543 784 952 5544 783 33 5545 800 1044 5546 804 928 5547 774 927 5548 772 938 5549 773 362 5550 775 1107 5551 805 1112 5552 767 618 5553 774 927 5554 809 947 5555 780 1099 5556 774 1098 5557 767 1169 5558 751 1119 5559 755 1486 5560 814 1031 5561 814 1031 5562 755 1486 5563 813 1048 5564 816 1116 5565 817 1071 5566 818 1030 5567 716 1072 5568 817 1071 5569 730 567 5570 724 1075 5571 765 1091 5572 764 1165 5573 596 331 5574 704 1488 5575 785 1110 5576 776 1171 5577 777 965 5578 780 964 5579 887 1172 5580 886 1061 5581 885 996 5582 880 987 5583 892 992 5584 891 1010 5585 879 1023 5586 886 1061 5587 887 1172 5588 868 626 5589 842 1138 5590 839 1140 5591 894 1058 5592 895 1057 5593 924 627 5594 898 449 5595 921 297 5596 922 628 5597 834 1136 5598 852 1490 5599 846 1174 5600 863 11 5601 860 11 5602 859 11 5603 906 100 5604 905 798 5605 873 99 5606 910 415 5607 909 143 5608 908 1175 5609 917 33 5610 920 33 5611 919 33 5612 921 1025 5613 917 1029 5614 918 631 5615 911 1156 5616 887 1172 5617 888 1151 5618 869 1146 5619 837 980 5620 830 1007 5621 719 1076 5622 806 1163 5623 807 1113 5624 846 1174 5625 843 994 5626 826 983 5627 931 1176 5628 961 1180 5629 960 1177 5630 970 1316 5631 971 1316 5632 968 1316 5633 961 1180 5634 995 1493 5635 996 1181 5636 967 1182 5637 964 1245 5638 965 1183 5639 968 1494 5640 975 1494 5641 974 1494 5642 986 40 5643 987 40 5644 984 40 5645 936 1187 5646 962 1217 5647 961 1188 5648 956 1190 5649 983 1243 5650 933 40 5651 942 11 5652 941 11 5653 952 1191 5654 984 1328 5655 957 1328 5656 989 1328 5657 954 1193 5658 967 1182 5659 990 1194 5660 992 1196 5661 953 1191 5662 952 1191 5663 983 328 5664 993 328 5665 991 328 5666 958 27 5667 957 27 5668 984 27 5669 955 1199 5670 948 1209 5671 947 1200 5672 951 1337 5673 940 1337 5674 939 1337 5675 949 1203 5676 938 1339 5677 944 1204 5678 977 1206 5679 966 1215 5680 965 1207 5681 948 1209 5682 955 1199 5683 958 1210 5684 953 1212 5685 992 1495 5686 994 1213 5687 947 1200 5688 949 1203 5689 959 1205 5690 996 1181 5691 995 1493 5692 966 1215 5693 938 27 5694 949 27 5695 934 27 5696 949 1496 5697 947 1496 5698 948 1496 5699 929 27 5700 949 27 5701 948 27 5702 937 1216 5703 963 1229 5704 962 1217 5705 974 1351 5706 975 1351 5707 972 1351 5708 981 1352 5709 974 1352 5710 973 1352 5711 973 1497 5712 972 1497 5713 951 1497 5714 971 1354 5715 964 1354 5716 975 1354 5717 965 1498 5718 964 1498 5719 971 1498 5720 942 1223 5721 953 1212 5722 959 1214 5723 945 1356 5724 982 1356 5725 950 1356 5726 951 1357 5727 972 1357 5728 946 1357 5729 989 1292 5730 957 1292 5731 935 1292 5732 988 1499 5733 958 1499 5734 987 1499 5735 990 1194 5736 962 1217 5737 963 1229 5738 989 328 5739 988 328 5740 986 328 5741 991 328 5742 993 328 5743 952 328 5744 994 1213 5745 992 1495 5746 956 1230 5747 995 1232 5748 961 1188 5749 962 1217 5750 979 1364 5751 970 1364 5752 969 1364 5753 958 1235 5754 955 1500 5755 956 1501 5756 956 1501 5757 930 1236 5758 958 1235 5759 930 1236 5760 935 1502 5761 957 1234 5762 976 1503 5763 965 1503 5764 970 1503 5765 969 1504 5766 974 1504 5767 981 1504 5768 941 328 5769 943 328 5770 954 328 5771 967 1182 5772 966 1184 5773 995 1232 5774 956 1190 5775 992 1196 5776 993 1197 5777 989 1244 5778 929 1505 5779 948 1209 5780 954 1193 5781 943 1506 5782 964 1245 5783 980 1507 5784 973 1507 5785 950 1507 5786 933 328 5787 983 328 5788 963 328 5789 931 1247 5790 932 1247 5791 1019 1248 5792 1029 1377 5793 1028 1377 5794 1027 1377 5795 1055 1251 5796 1054 1283 5797 1020 1249 5798 1024 1252 5799 1023 1311 5800 1026 1253 5801 1027 1508 5802 1028 1508 5803 1033 1508 5804 1045 1186 5805 1044 1186 5806 1043 1186 5807 936 1187 5808 931 1189 5809 1020 1256 5810 933 40 5811 1042 1308 5812 1015 1258 5813 1011 1259 5814 1000 33 5815 1001 33 5816 1043 1389 5817 1044 1389 5818 1048 1389 5819 1013 1262 5820 1050 1295 5821 1049 1263 5822 1011 1259 5823 1012 1260 5824 1051 1264 5825 1050 1509 5826 1052 1509 5827 1042 1509 5828 1043 27 5829 1016 27 5830 1017 27 5831 1014 1267 5832 1053 1282 5833 1006 1268 5834 1010 1399 5835 1009 1399 5836 998 1399 5837 1008 1271 5838 1018 1281 5839 1003 1272 5840 1036 1274 5841 1035 1510 5842 1024 1275 5843 1007 1269 5844 1047 1511 5845 1017 1277 5846 1053 1278 5847 1051 1297 5848 1012 1279 5849 1018 1281 5850 1008 1271 5851 1006 1268 5852 1055 1251 5853 1036 1274 5854 1025 1276 5855 1006 1512 5856 1008 1512 5857 1007 1512 5858 1008 27 5859 997 27 5860 934 27 5861 929 27 5862 1008 27 5863 934 27 5864 1021 1257 5865 1022 1294 5866 937 1216 5867 1033 1413 5868 1032 1413 5869 1031 1413 5870 1040 1414 5871 1039 1414 5872 1032 1414 5873 1010 1513 5874 1031 1513 5875 1032 1513 5876 1030 1416 5877 1027 1416 5878 1034 1416 5879 1030 1514 5880 1023 1514 5881 1024 1514 5882 1001 1289 5883 1003 1515 5884 1018 1280 5885 1004 1420 5886 998 1420 5887 1009 1420 5888 1010 1421 5889 999 1421 5890 1005 1421 5891 1048 1516 5892 929 1516 5893 935 1516 5894 1046 1517 5895 1017 1517 5896 1047 1517 5897 1022 1294 5898 1021 1257 5899 1049 1263 5900 1045 328 5901 1047 328 5902 1048 328 5903 1050 328 5904 1013 328 5905 1011 328 5906 1053 1278 5907 1014 1518 5908 1015 1296 5909 1021 1257 5910 1020 1256 5911 1054 1298 5912 1038 1427 5913 1037 1427 5914 1028 1427 5915 1015 1519 5916 1014 1500 5917 1017 1300 5918 1016 1301 5919 935 1520 5920 930 1302 5921 1015 1519 5922 1017 1300 5923 930 1302 5924 1029 1521 5925 1024 1521 5926 1035 1521 5927 1028 1522 5928 1037 1522 5929 1040 1522 5930 1000 1433 5931 1011 1433 5932 1013 1433 5933 1026 1253 5934 1049 1263 5935 1054 1298 5936 1052 1265 5937 1051 1264 5938 1015 1258 5939 1048 1309 5940 1047 1511 5941 1007 1269 5942 1023 1311 5943 1002 1523 5944 1013 1262 5945 1009 1524 5946 1032 1524 5947 1039 1524 5948 933 328 5949 937 328 5950 1022 328 5951 1058 1313 5952 1059 1525 5953 1077 1314 5954 1087 1179 5955 1086 1179 5956 1085 1179 5957 1113 1317 5958 1112 1349 5959 1078 1315 5960 1082 1318 5961 1081 1373 5962 1084 1319 5963 1085 1526 5964 1086 1526 5965 1091 1526 5966 1103 1384 5967 1102 1384 5968 1101 1384 5969 1062 1322 5970 1058 1386 5971 1078 1323 5972 1060 331 5973 1100 1370 5974 1073 1325 5975 1069 1326 5976 941 11 5977 942 11 5978 1101 1192 5979 1102 1192 5980 1106 1192 5981 1071 1329 5982 1108 1360 5983 1107 1330 5984 1069 1326 5985 1070 1327 5986 1109 1331 5987 1108 1527 5988 1110 1527 5989 1100 1527 5990 1101 27 5991 1074 27 5992 1075 27 5993 1072 1334 5994 1111 1348 5995 1064 1335 5996 1068 1202 5997 1067 1202 5998 939 1202 5999 1066 1338 6000 1076 1347 6001 944 1204 6002 1094 1340 6003 1093 1528 6004 1082 1341 6005 1065 1336 6006 1105 1529 6007 1075 1343 6008 1111 1344 6009 1109 1362 6010 1070 1345 6011 1076 1347 6012 1066 1338 6013 1064 1335 6014 1113 1317 6015 1094 1340 6016 1083 1342 6017 1064 1530 6018 1066 1530 6019 1065 1530 6020 1066 27 6021 938 27 6022 934 27 6023 1056 27 6024 1066 27 6025 934 27 6026 1079 1324 6027 1080 1359 6028 1063 1350 6029 1091 1218 6030 1090 1218 6031 1089 1218 6032 1098 1219 6033 1097 1219 6034 1090 1219 6035 1068 1531 6036 1089 1531 6037 1090 1531 6038 1088 1221 6039 1085 1221 6040 1092 1221 6041 1088 1532 6042 1081 1532 6043 1082 1532 6044 942 1223 6045 944 1224 6046 1076 1346 6047 945 1225 6048 939 1225 6049 1067 1225 6050 1068 1226 6051 940 1226 6052 946 1226 6053 1106 1533 6054 1056 1533 6055 1061 1533 6056 1104 1534 6057 1075 1534 6058 1105 1534 6059 1080 1359 6060 1079 1324 6061 1107 1330 6062 1103 328 6063 1105 328 6064 1106 328 6065 1108 328 6066 1071 328 6067 1069 328 6068 1111 1344 6069 1072 1535 6070 1073 1361 6071 1079 1324 6072 1078 1323 6073 1112 1363 6074 1096 1233 6075 1095 1233 6076 1086 1233 6077 1073 1536 6078 1072 1537 6079 1075 1365 6080 1074 1366 6081 1061 1367 6082 1057 1367 6083 1073 1536 6084 1075 1365 6085 1057 1367 6086 1087 1538 6087 1082 1538 6088 1093 1538 6089 1086 1539 6090 1095 1539 6091 1098 1539 6092 941 1239 6093 1069 1239 6094 1071 1239 6095 1084 1319 6096 1107 1330 6097 1112 1363 6098 1110 1332 6099 1109 1331 6100 1073 1325 6101 1106 1371 6102 1105 1529 6103 1065 1336 6104 1081 1373 6105 943 1540 6106 1071 1329 6107 1067 1541 6108 1090 1541 6109 1097 1541 6110 1060 328 6111 1063 328 6112 1080 328 6113 1058 1375 6114 1128 1378 6115 1127 1376 6116 1137 1250 6117 1138 1250 6118 1135 1250 6119 1128 1378 6120 1162 1542 6121 1163 1379 6122 1134 1380 6123 1131 1439 6124 1132 1381 6125 1135 1543 6126 1142 1543 6127 1141 1543 6128 1153 331 6129 1154 331 6130 1151 331 6131 1062 1322 6132 1129 1412 6133 1128 1385 6134 1123 1387 6135 1150 1437 6136 1060 331 6137 1001 33 6138 1000 33 6139 1119 1388 6140 1151 1261 6141 1124 1261 6142 1156 1261 6143 1121 1390 6144 1134 1380 6145 1157 1391 6146 1159 1393 6147 1120 1388 6148 1119 1388 6149 1150 328 6150 1160 328 6151 1158 328 6152 1125 27 6153 1124 27 6154 1151 27 6155 1122 1396 6156 1115 1405 6157 1114 1397 6158 1118 1270 6159 999 1270 6160 998 1270 6161 1116 1400 6162 997 1273 6163 1003 1272 6164 1144 1402 6165 1133 1411 6166 1132 1403 6167 1115 1405 6168 1122 1396 6169 1125 1406 6170 1120 1408 6171 1159 1544 6172 1161 1409 6173 1114 1397 6174 1116 1400 6175 1126 1401 6176 1163 1379 6177 1162 1542 6178 1133 1411 6179 997 27 6180 1116 27 6181 934 27 6182 1116 1545 6183 1114 1545 6184 1115 1545 6185 1056 27 6186 1116 27 6187 1115 27 6188 1063 1350 6189 1130 1423 6190 1129 1412 6191 1141 1546 6192 1142 1546 6193 1139 1546 6194 1148 1285 6195 1141 1285 6196 1140 1285 6197 1140 1547 6198 1139 1547 6199 1118 1547 6200 1138 1548 6201 1131 1548 6202 1142 1548 6203 1132 1549 6204 1131 1549 6205 1138 1549 6206 1001 1418 6207 1120 1408 6208 1126 1410 6209 1004 1290 6210 1149 1290 6211 1117 1290 6212 1118 1550 6213 1139 1550 6214 1005 1550 6215 1156 1358 6216 1124 1358 6217 1061 1358 6218 1155 1551 6219 1125 1551 6220 1154 1551 6221 1157 1391 6222 1129 1412 6223 1130 1423 6224 1156 328 6225 1155 328 6226 1153 328 6227 1158 328 6228 1160 328 6229 1119 328 6230 1161 1409 6231 1159 1544 6232 1123 1424 6233 1162 1426 6234 1128 1385 6235 1129 1412 6236 1146 1299 6237 1137 1299 6238 1136 1299 6239 1125 1429 6240 1122 1537 6241 1123 1552 6242 1123 1552 6243 1057 1430 6244 1125 1429 6245 1057 1430 6246 1061 1553 6247 1124 1428 6248 1143 1554 6249 1132 1554 6250 1137 1554 6251 1136 1555 6252 1141 1555 6253 1148 1555 6254 1000 328 6255 1002 328 6256 1121 328 6257 1134 1380 6258 1133 1382 6259 1162 1426 6260 1123 1387 6261 1159 1393 6262 1160 1394 6263 1156 1438 6264 1056 1556 6265 1115 1405 6266 1121 1390 6267 1002 1557 6268 1131 1439 6269 1147 1558 6270 1140 1558 6271 1117 1558 6272 1060 328 6273 1150 328 6274 1130 328 6275

- - - 0.010000 0.000000 0.000000 0.000000 0.000000 0.010000 0.000000 -0.000000 0.000000 0.000000 0.010000 0.000000 0.000000 0.000000 0.000000 1.000000 - + + + 0.01 0 0 0 0 0.01 0 0 0 0 0.01 0 0 0 0 1 + - + + + - - - 1.000000 - - - - - 30.000000 - - - 0.000000 - 3.333333 - - - +
diff --git a/vrx_urdf/wamv_description/urdf/cpu_cases.xacro b/vrx_urdf/wamv_description/urdf/cpu_cases.xacro index 626d139f2..45cd6697e 100644 --- a/vrx_urdf/wamv_description/urdf/cpu_cases.xacro +++ b/vrx_urdf/wamv_description/urdf/cpu_cases.xacro @@ -2,12 +2,27 @@ - + + @@ -37,6 +52,29 @@ + + + 0.073 0 -1.53 0 0 0 + + + https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases.dae + + + + 1.0 1.0 1.0 + 1.0 1.0 1.0 + + + https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases_Albedo.png + https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases_Normal.png + https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases_Roughness.png + https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases_Metalness.png + + + + + + From ee1072dde7f32288831bec35f08923290f27aa27 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Thu, 17 Nov 2022 22:05:45 +0100 Subject: [PATCH 10/14] Clean MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/models/dock_2022/model.sdf | 190 +----------------------------- 1 file changed, 4 insertions(+), 186 deletions(-) diff --git a/vrx_gz/models/dock_2022/model.sdf b/vrx_gz/models/dock_2022/model.sdf index 2a10f0dbe..fc96d3273 100644 --- a/vrx_gz/models/dock_2022/model.sdf +++ b/vrx_gz/models/dock_2022/model.sdf @@ -115,67 +115,6 @@ link_symbols - - - - - - @@ -284,67 +223,6 @@ link_symbols - - - - - - - - @@ -453,70 +331,11 @@ link_symbols - - - - - - - + + Date: Thu, 17 Nov 2022 22:12:51 +0100 Subject: [PATCH 11/14] Restore MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- .../models/cpu_cases/mesh/cpu_cases.dae | 9610 ++++++++++++++++- .../wamv_description/urdf/cpu_cases.xacro | 42 +- 2 files changed, 9552 insertions(+), 100 deletions(-) diff --git a/vrx_urdf/vrx_gazebo/models/cpu_cases/mesh/cpu_cases.dae b/vrx_urdf/vrx_gazebo/models/cpu_cases/mesh/cpu_cases.dae index 89e0437b3..f2a406fe5 100644 --- a/vrx_urdf/vrx_gazebo/models/cpu_cases/mesh/cpu_cases.dae +++ b/vrx_urdf/vrx_gazebo/models/cpu_cases/mesh/cpu_cases.dae @@ -1,115 +1,9605 @@ - + - Blender User - Blender 3.3.1 commit date:2022-10-04, commit time:18:35, hash:b292cfe5a936 + FBX COLLADA exporter - 2022-11-13T14:54:13 - 2022-11-13T14:54:13 - + 2019-05-07T18:12:40Z + 2019-05-07T18:12:40Z + Z_UP + + + cpu_cases.png + + + + + + + - + - - - battery_Albedo_png - - - - - battery_Albedo_png-surface - - - - + + - 0 0 0 1 + 0.000000 0.000000 0.000000 1.000000 + + 0.588235 0.588235 0.588235 1.000000 + - + + + + TRUE + TRUE + ADD + + + - - 1.45 - - + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + - - - cpu_cases_Albedo.png - - - - - - - - + - - -16.59355 -35.26818 129.6871 -15.77042 -37.73759 129.6871 -13.301 -38.56072 129.6871 -14.53328 -39.45044 176.007 -16.4872 -39.0051 176.007 -16.93254 -37.05117 176.007 -13.5064 -39.63248 130.6999 -14.87107 -41.53192 164.6898 -17.64937 -35.48951 130.6999 -19.01404 -37.38895 164.6898 -14.87106 -41.53192 173.8982 -19.01403 -37.38895 173.8982 -16.61363 -38.59674 130.6999 -17.9783 -40.49618 164.6898 -17.97829 -40.49618 173.8982 -14.78661 -41.01155 175.4798 -18.49366 -37.30451 175.4798 -17.60552 -40.12341 175.4798 -14.19095 -25.83975 129.6871 -14.19095 -5.731884 129.6871 -16.59355 -25.83975 129.6871 -17.64937 -25.83975 130.6999 -18.7535 -25.83975 158.2004 -16.59355 -5.731884 129.6871 -17.64937 -5.731883 130.6999 -18.7535 -5.731882 158.2004 -18.81582 -7.284054 159.7526 -18.81582 -24.28758 159.7526 -18.80024 -25.4517 159.3645 -18.80024 -6.119925 159.3645 -14.19095 -5.731883 158.2004 -14.19095 -6.119926 159.3645 -14.19095 -7.284054 159.7526 -14.19095 -25.83975 158.2004 -14.19095 -25.4517 159.3645 -14.19095 -24.28758 159.7526 6.260983 -36.31864 129.6871 -8.506462 -36.31864 129.6871 6.260983 -38.56072 129.6871 6.260983 -39.63248 130.6999 6.260983 -41.16928 158.2004 -8.506462 -38.56072 129.6871 -8.506462 -39.63248 130.6999 -8.506462 -41.16928 158.2004 -6.954288 -41.25602 159.7526 4.708812 -41.25602 159.7526 5.872939 -41.23434 159.3645 -8.118417 -41.23434 159.3645 -6.954288 -36.31864 159.7526 -8.118417 -36.31864 159.3645 -8.506462 -36.31864 158.2004 6.260983 -36.31865 158.2004 5.87294 -36.31865 159.3645 4.708813 -36.31865 159.7526 -15.69215 -5.731886 176.007 -15.69215 -25.83975 176.007 -19.01403 -25.83975 173.8982 -18.49366 -25.83975 175.4798 -16.93254 -25.83975 176.007 -19.01404 -25.83975 170.3869 -19.01403 -5.731886 173.8982 -19.01404 -5.731886 170.3869 -18.49366 -5.731886 175.4798 -16.93254 -5.731886 176.007 -19.01404 -24.28758 168.8348 -19.01404 -7.284057 168.8348 -19.01404 -25.4517 169.2228 -19.01404 -6.119928 169.2228 -15.69215 -5.731886 170.3869 -15.69215 -6.119929 169.2228 -15.69215 -7.284058 168.8348 -15.69215 -24.28758 168.8348 -15.69215 -25.45171 169.2228 -15.69215 -25.83975 170.3869 -8.506462 -38.14337 176.007 6.26098 -38.14337 176.007 6.26098 -39.45044 176.007 6.260979 -41.53192 173.8982 6.260979 -41.01155 175.4798 6.260979 -41.53192 170.3869 -8.506462 -41.01155 175.4798 -8.506462 -41.53192 173.8982 -8.506462 -41.53192 170.3869 -8.506462 -39.45044 176.007 4.708809 -41.53192 168.8348 -6.954289 -41.53192 168.8348 5.872936 -41.53192 169.2228 -8.118417 -41.53192 169.2228 -6.954289 -38.14337 168.8348 -8.118417 -38.14337 169.2228 4.708809 -38.14337 168.8348 5.872936 -38.14337 169.2228 6.26098 -38.14337 170.3869 -8.506462 -38.14337 170.3869 -19.01404 -7.312862 164.6898 -19.01404 -24.281 164.6898 -19.01404 -25.4423 164.6898 -19.01404 -6.15367 164.6898 -19.01404 -37.38895 170.3869 -17.9783 -40.49618 170.3869 -14.87106 -41.53192 170.3869 -19.01404 -37.38895 169.2228 -17.9783 -40.49618 169.2228 -14.87106 -41.53192 169.2228 -7.025945 -41.53192 164.6898 -8.196287 -41.53192 164.6898 -14.65726 -41.23434 159.3645 -17.76449 -40.1986 159.3645 -18.80024 -37.09137 159.3645 -18.7535 -37.02631 158.2004 -17.71776 -40.13354 158.2004 -14.61053 -41.16928 158.2004 4.637154 -41.53192 164.6898 5.795068 -41.53192 164.6898 10.9723 -41.16927 158.2004 10.9723 -37.03272 176.007 -16.93254 0 176.007 10.9723 -38.56072 129.6871 10.9723 -39.63248 130.6999 10.9723 -41.01155 175.4798 10.9723 -41.23437 159.3646 10.9723 -41.53192 170.3869 -18.49366 0 175.4798 -19.01404 0 169.2228 -1.103743 -38.70043 156.9494 -1.103743 -37.47573 156.9494 -1.103743 -37.47573 146.3776 4.718322 -39.31754 150.5315 5.581581 -39.31754 152.7816 5.581581 -39.31754 146.6534 4.718322 -39.31754 146.8221 2.310718 -39.31753 155.0093 1.734024 -39.31754 152.1198 3.593332 -39.31754 145.0054 3.544307 -39.31754 145.8813 4.425677 -39.31754 146.1679 5.012148 -39.31754 145.5043 5.074028 -39.31754 153.9384 4.304079 -39.31754 151.1949 3.405956 -39.31754 151.6906 4.062416 -39.31753 155.0093 4.229142 -38.70039 149.8702 4.229143 -38.70039 146.9177 4.229142 -37.47573 146.9177 4.229142 -37.47573 149.8702 6.070762 -38.70039 153.8347 6.070762 -37.47573 153.8347 6.070762 -37.47573 146.5578 6.070762 -38.70039 146.5578 2.568247 -38.70043 156.9494 2.568247 -37.47573 156.9494 1.598726 -38.70039 151.5133 1.598726 -37.47573 151.5133 3.621114 -38.70039 144.5091 5.344482 -38.70039 145.1282 5.344482 -37.47573 145.1282 3.621114 -37.47573 144.5091 4.093343 -38.70039 146.544 3.516525 -38.70039 146.3776 3.516525 -37.47573 146.3776 4.093343 -37.47573 146.544 6.25433 -38.70043 156.9494 6.25433 -37.47573 156.9494 6.25433 -38.70043 155.0093 6.25433 -39.31753 155.9738 6.25433 -37.47573 155.9738 6.25433 -37.47573 155.0093 5.392851 -38.70042 155.0093 5.392851 -37.47573 155.0093 3.927212 -38.70039 150.4831 3.927212 -37.47573 150.4831 3.170327 -38.70039 151.0378 3.170327 -37.47573 151.0378 2.438744 -39.31753 155.9738 -1.103743 -39.31754 145.874 -1.103743 -37.47573 151.6167 -1.103743 -38.70039 146.3776 -1.103743 -37.47573 144.4816 -1.103743 -39.31753 155.9738 -6.925807 -39.31754 150.5315 -6.925807 -39.31754 146.8221 -7.789065 -39.31754 146.6534 -7.789065 -39.31754 152.7816 -1.103743 -39.31754 152.2433 -3.941508 -39.31754 152.1198 -4.518202 -39.31753 155.0093 -1.103743 -39.31753 155.0093 -5.800817 -39.31754 145.0054 -7.219634 -39.31754 145.5043 -6.633162 -39.31754 146.1679 -5.751792 -39.31754 145.8813 -7.281514 -39.31754 153.9384 -6.269902 -39.31753 155.0093 -5.613441 -39.31754 151.6906 -6.511563 -39.31754 151.1949 -1.103743 -39.31754 144.9852 -6.436627 -38.70039 149.8702 -6.436627 -37.47573 149.8702 -6.436627 -37.47573 146.9177 -6.436629 -38.70039 146.9177 -8.278247 -38.70039 153.8347 -8.278247 -38.70039 146.5578 -8.278247 -37.47573 146.5578 -8.278247 -37.47573 153.8347 -4.775732 -38.70043 156.9494 -4.775732 -37.47573 156.9494 -1.103743 -38.70039 151.6167 -3.806211 -37.47573 151.5133 -3.806211 -38.70039 151.5133 -5.828599 -38.70039 144.5091 -5.828599 -37.47573 144.5091 -7.551967 -37.47573 145.1282 -7.551967 -38.70039 145.1282 -6.300828 -38.70039 146.544 -6.300828 -37.47573 146.544 -5.72401 -37.47573 146.3776 -5.72401 -38.70039 146.3776 -8.461814 -38.70043 156.9494 -8.461814 -37.47573 156.9494 -8.461814 -38.70043 155.0093 -8.461814 -37.47573 155.0093 -8.461814 -37.47573 155.9738 -8.461814 -39.31753 155.9738 -7.600337 -38.70042 155.0093 -7.600337 -37.47573 155.0093 -6.134698 -38.70039 150.4831 -6.134698 -37.47573 150.4831 -1.103743 -38.70039 144.4816 -5.377812 -37.47573 151.0378 -5.377812 -38.70039 151.0378 -4.646229 -39.31753 155.9738 10.9723 -41.53192 173.8982 10.9723 -39.45044 176.007 10.9723 -41.53192 164.6898 10.9723 -41.53192 169.2228 -17.64937 0 130.6999 -16.59355 0 129.6871 -18.75353 0 158.2004 -19.01404 0 164.6898 10.9723 0 176.007 -19.01403 0 173.8982 -19.01404 0 170.3869 -18.80021 0 159.3646 -15.69215 0 176.007 38.53815 -35.26818 129.6871 37.71501 -37.73759 129.6871 35.2456 -38.56072 129.6871 36.47788 -39.45044 176.007 38.4318 -39.0051 176.007 38.87714 -37.05117 176.007 35.451 -39.63248 130.6999 36.81567 -41.53192 164.6898 39.59397 -35.48951 130.6999 40.95864 -37.38895 164.6898 36.81566 -41.53192 173.8982 40.95863 -37.38895 173.8982 38.55823 -38.59674 130.6999 39.9229 -40.49618 164.6898 39.92289 -40.49618 173.8982 36.73121 -41.01155 175.4798 40.43826 -37.30451 175.4798 39.55012 -40.12341 175.4798 36.13555 -25.83975 129.6871 36.13554 -5.731884 129.6871 38.53815 -25.83975 129.6871 39.59397 -25.83975 130.6999 40.6981 -25.83975 158.2004 38.53815 -5.731884 129.6871 39.59397 -5.731883 130.6999 40.6981 -5.731882 158.2004 40.76041 -7.284054 159.7526 40.76041 -24.28758 159.7526 40.74483 -25.4517 159.3645 40.74483 -6.119925 159.3645 36.13555 -5.731883 158.2004 36.13555 -6.119926 159.3645 36.13555 -7.284054 159.7526 36.13555 -25.83975 158.2004 36.13555 -25.4517 159.3645 36.13555 -24.28758 159.7526 15.68362 -36.31864 129.6871 30.45106 -36.31864 129.6871 15.68362 -38.56072 129.6871 15.68362 -39.63248 130.6999 15.68362 -41.16928 158.2004 30.45106 -38.56072 129.6871 30.45106 -39.63248 130.6999 30.45106 -41.16928 158.2004 28.89889 -41.25602 159.7526 17.23579 -41.25602 159.7526 16.07166 -41.23434 159.3645 30.06302 -41.23434 159.3645 28.89889 -36.31864 159.7526 30.06302 -36.31864 159.3645 30.45106 -36.31864 158.2004 15.68362 -36.31865 158.2004 16.07166 -36.31865 159.3645 17.23579 -36.31865 159.7526 37.63675 -5.731886 176.007 37.63675 -25.83975 176.007 40.95863 -25.83975 173.8982 40.43826 -25.83975 175.4798 38.87714 -25.83975 176.007 40.95864 -25.83975 170.3869 40.95863 -5.731886 173.8982 40.95864 -5.731886 170.3869 40.43826 -5.731886 175.4798 38.87714 -5.731886 176.007 40.95864 -24.28758 168.8348 40.95864 -7.284057 168.8348 40.95864 -25.4517 169.2228 40.95864 -6.119928 169.2228 37.63675 -5.731886 170.3869 37.63675 -6.119929 169.2228 37.63675 -7.284058 168.8348 37.63675 -24.28758 168.8348 37.63675 -25.45171 169.2228 37.63675 -25.83975 170.3869 30.45106 -38.14337 176.007 15.68362 -38.14337 176.007 15.68362 -39.45044 176.007 15.68362 -41.53192 173.8982 15.68362 -41.01155 175.4798 15.68362 -41.53192 170.3869 30.45106 -41.01155 175.4798 30.45106 -41.53192 173.8982 30.45106 -41.53192 170.3869 30.45106 -39.45044 176.007 17.23579 -41.53192 168.8348 28.89889 -41.53192 168.8348 16.07166 -41.53192 169.2228 30.06302 -41.53192 169.2228 28.89889 -38.14337 168.8348 30.06302 -38.14337 169.2228 17.23579 -38.14337 168.8348 16.07166 -38.14337 169.2228 15.68362 -38.14337 170.3869 30.45106 -38.14337 170.3869 40.95864 -7.312862 164.6898 40.95864 -24.281 164.6898 40.95864 -25.4423 164.6898 40.95864 -6.15367 164.6898 40.95864 -37.38895 170.3869 39.92289 -40.49618 170.3869 36.81566 -41.53192 170.3869 40.95864 -37.38895 169.2228 39.92289 -40.49618 169.2228 36.81566 -41.53192 169.2228 28.97055 -41.53192 164.6898 30.14089 -41.53192 164.6898 36.60186 -41.23434 159.3645 39.70909 -40.1986 159.3645 40.74483 -37.09137 159.3645 40.6981 -37.02631 158.2004 39.66235 -40.13354 158.2004 36.55513 -41.16928 158.2004 17.30745 -41.53192 164.6898 16.14953 -41.53192 164.6898 38.87714 0 176.007 40.43826 0 175.4798 40.95864 0 169.2228 23.04834 -38.70043 156.9494 23.04834 -37.47573 156.9494 23.04834 -37.47573 146.3776 17.22628 -39.31754 150.5315 16.36302 -39.31754 152.7816 16.36302 -39.31754 146.6534 17.22628 -39.31754 146.8221 19.63388 -39.31753 155.0093 20.21058 -39.31754 152.1198 18.35127 -39.31754 145.0054 18.40029 -39.31754 145.8813 17.51892 -39.31754 146.1679 16.93245 -39.31754 145.5043 16.87057 -39.31754 153.9384 17.64052 -39.31754 151.1949 18.53864 -39.31754 151.6906 17.88218 -39.31753 155.0093 17.71546 -38.70039 149.8702 17.71546 -38.70039 146.9177 17.71546 -37.47573 146.9177 17.71546 -37.47573 149.8702 15.87384 -38.70039 153.8347 15.87384 -37.47573 153.8347 15.87384 -37.47573 146.5578 15.87384 -38.70039 146.5578 19.37635 -38.70043 156.9494 19.37635 -37.47573 156.9494 20.34587 -38.70039 151.5133 20.34587 -37.47573 151.5133 18.32349 -38.70039 144.5091 16.60012 -38.70039 145.1282 16.60012 -37.47573 145.1282 18.32349 -37.47573 144.5091 17.85126 -38.70039 146.544 18.42807 -38.70039 146.3776 18.42807 -37.47573 146.3776 17.85126 -37.47573 146.544 15.69027 -38.70043 156.9494 15.69027 -37.47573 156.9494 15.69027 -38.70043 155.0093 15.69027 -39.31753 155.9738 15.69027 -37.47573 155.9738 15.69027 -37.47573 155.0093 16.55175 -38.70042 155.0093 16.55175 -37.47573 155.0093 18.01739 -38.70039 150.4831 18.01739 -37.47573 150.4831 18.77427 -38.70039 151.0378 18.77427 -37.47573 151.0378 19.50586 -39.31753 155.9738 23.04834 -39.31754 145.874 23.04834 -37.47573 151.6167 23.04834 -38.70039 146.3776 23.04834 -37.47573 144.4816 23.04834 -39.31753 155.9738 28.87041 -39.31754 150.5315 28.87041 -39.31754 146.8221 29.73366 -39.31754 146.6534 29.73366 -39.31754 152.7816 23.04834 -39.31754 152.2433 25.88611 -39.31754 152.1198 26.4628 -39.31753 155.0093 23.04834 -39.31753 155.0093 27.74542 -39.31754 145.0054 29.16423 -39.31754 145.5043 28.57776 -39.31754 146.1679 27.69639 -39.31754 145.8813 29.22611 -39.31754 153.9384 28.2145 -39.31753 155.0093 27.55804 -39.31754 151.6906 28.45616 -39.31754 151.1949 23.04834 -39.31754 144.9852 28.38123 -38.70039 149.8702 28.38123 -37.47573 149.8702 28.38123 -37.47573 146.9177 28.38123 -38.70039 146.9177 30.22285 -38.70039 153.8347 30.22285 -38.70039 146.5578 30.22285 -37.47573 146.5578 30.22285 -37.47573 153.8347 26.72033 -38.70043 156.9494 26.72033 -37.47573 156.9494 23.04834 -38.70039 151.6167 25.75081 -37.47573 151.5133 25.75081 -38.70039 151.5133 27.7732 -38.70039 144.5091 27.7732 -37.47573 144.5091 29.49657 -37.47573 145.1282 29.49657 -38.70039 145.1282 28.24543 -38.70039 146.544 28.24543 -37.47573 146.544 27.66861 -37.47573 146.3776 27.66861 -38.70039 146.3776 30.40641 -38.70043 156.9494 30.40641 -37.47573 156.9494 30.40641 -38.70043 155.0093 30.40641 -37.47573 155.0093 30.40641 -37.47573 155.9738 30.40641 -39.31753 155.9738 29.54494 -38.70042 155.0093 29.54494 -37.47573 155.0093 28.0793 -38.70039 150.4831 28.0793 -37.47573 150.4831 23.04834 -38.70039 144.4816 27.32241 -37.47573 151.0378 27.32241 -38.70039 151.0378 26.59083 -39.31753 155.9738 39.59397 0 130.6999 38.53815 0 129.6871 40.69812 0 158.2004 40.95864 0 164.6898 40.95863 0 173.8982 40.95864 0 170.3869 40.74481 0 159.3646 37.63675 0 176.007 -16.59355 35.26818 129.6871 -15.77042 37.73759 129.6871 -13.301 38.56072 129.6871 -14.53328 39.45044 176.007 -16.4872 39.0051 176.007 -16.93254 37.05117 176.007 -13.5064 39.63248 130.6999 -14.87107 41.53192 164.6898 -17.64937 35.48951 130.6999 -19.01404 37.38895 164.6898 -14.87106 41.53192 173.8982 -19.01403 37.38895 173.8982 -16.61363 38.59674 130.6999 -17.9783 40.49618 164.6898 -17.9783 40.49618 173.8982 -14.78662 41.01155 175.4798 -18.49366 37.30451 175.4798 -17.60552 40.12341 175.4798 -14.19095 25.83975 129.6871 -14.19095 5.731884 129.6871 -16.59355 25.83975 129.6871 -17.64937 25.83975 130.6999 -18.7535 25.83975 158.2004 -16.59355 5.731884 129.6871 -17.64937 5.731883 130.6999 -18.7535 5.731882 158.2004 -18.81582 7.284054 159.7526 -18.81582 24.28758 159.7526 -18.80024 25.4517 159.3645 -18.80024 6.119925 159.3645 -14.19095 5.731883 158.2004 -14.19095 6.119926 159.3645 -14.19095 7.284054 159.7526 -14.19095 25.83975 158.2004 -14.19095 25.4517 159.3645 -14.19095 24.28758 159.7526 6.260982 36.31864 129.6871 -8.506463 36.31864 129.6871 6.260982 38.56072 129.6871 6.260982 39.63248 130.6999 6.260982 41.16928 158.2004 -8.506463 38.56072 129.6871 -8.506463 39.63248 130.6999 -8.506463 41.16928 158.2004 -6.954289 41.25602 159.7526 4.708811 41.25602 159.7526 5.872938 41.23434 159.3645 -8.118418 41.23434 159.3645 -6.954289 36.31864 159.7526 -8.118418 36.31864 159.3645 -8.506463 36.31864 158.2004 6.260982 36.31865 158.2004 5.872939 36.31865 159.3645 4.708812 36.31865 159.7526 -15.69215 5.731886 176.007 -15.69216 25.83975 176.007 -19.01403 25.83975 173.8982 -18.49366 25.83975 175.4798 -16.93254 25.83975 176.007 -19.01404 25.83975 170.3869 -19.01403 5.731886 173.8982 -19.01404 5.731886 170.3869 -18.49366 5.731886 175.4798 -16.93254 5.731886 176.007 -19.01404 24.28758 168.8348 -19.01404 7.284057 168.8348 -19.01404 25.4517 169.2228 -19.01404 6.119928 169.2228 -15.69215 5.731886 170.3869 -15.69215 6.119929 169.2228 -15.69215 7.284058 168.8348 -15.69216 24.28758 168.8348 -15.69216 25.45171 169.2228 -15.69216 25.83975 170.3869 -8.506463 38.14337 176.007 6.260979 38.14337 176.007 6.260979 39.45044 176.007 6.260978 41.53192 173.8982 6.260978 41.01155 175.4798 6.260978 41.53192 170.3869 -8.506463 41.01155 175.4798 -8.506463 41.53192 173.8982 -8.506463 41.53192 170.3869 -8.506463 39.45044 176.007 4.708808 41.53192 168.8348 -6.95429 41.53192 168.8348 5.872935 41.53192 169.2228 -8.118418 41.53192 169.2228 -6.95429 38.14337 168.8348 -8.118418 38.14337 169.2228 4.708808 38.14337 168.8348 5.872935 38.14337 169.2228 6.260979 38.14337 170.3869 -8.506463 38.14337 170.3869 -19.01404 7.312862 164.6898 -19.01404 24.281 164.6898 -19.01404 25.4423 164.6898 -19.01404 6.15367 164.6898 -19.01404 37.38895 170.3869 -17.9783 40.49618 170.3869 -14.87106 41.53192 170.3869 -19.01404 37.38895 169.2228 -17.9783 40.49618 169.2228 -14.87106 41.53192 169.2228 -7.025946 41.53192 164.6898 -8.196288 41.53192 164.6898 -14.65726 41.23434 159.3645 -17.76449 40.1986 159.3645 -18.80024 37.09137 159.3645 -18.7535 37.02631 158.2004 -17.71776 40.13354 158.2004 -14.61053 41.16928 158.2004 4.637153 41.53192 164.6898 5.795067 41.53192 164.6898 10.9723 41.16927 158.2004 10.9723 37.03272 176.007 10.9723 38.56072 129.6871 10.9723 39.63248 130.6999 10.9723 41.01155 175.4798 10.9723 41.23437 159.3646 10.9723 41.53192 170.3869 -1.103744 38.70043 156.9494 -1.103744 37.47573 156.9494 -1.103744 37.47573 146.3776 4.718321 39.31754 150.5315 5.58158 39.31754 152.7816 5.58158 39.31754 146.6534 4.718321 39.31754 146.8221 2.310717 39.31753 155.0093 1.734023 39.31754 152.1198 3.593331 39.31754 145.0054 3.544306 39.31754 145.8813 4.425676 39.31754 146.1679 5.012147 39.31754 145.5043 5.074027 39.31754 153.9384 4.304078 39.31754 151.1949 3.405955 39.31754 151.6906 4.062415 39.31753 155.0093 4.229141 38.70039 149.8702 4.229142 38.70039 146.9177 4.229141 37.47573 146.9177 4.229141 37.47573 149.8702 6.070761 38.70039 153.8347 6.070761 37.47573 153.8347 6.070761 37.47573 146.5578 6.070761 38.70039 146.5578 2.568246 38.70043 156.9494 2.568246 37.47573 156.9494 1.598725 38.70039 151.5133 1.598725 37.47573 151.5133 3.621113 38.70039 144.5091 5.344481 38.70039 145.1282 5.344481 37.47573 145.1282 3.621113 37.47573 144.5091 4.093342 38.70039 146.544 3.516524 38.70039 146.3776 3.516524 37.47573 146.3776 4.093342 37.47573 146.544 6.254329 38.70043 156.9494 6.254329 37.47573 156.9494 6.254329 38.70043 155.0093 6.254329 39.31753 155.9738 6.254329 37.47573 155.9738 6.254329 37.47573 155.0093 5.39285 38.70042 155.0093 5.39285 37.47573 155.0093 3.927211 38.70039 150.4831 3.927211 37.47573 150.4831 3.170326 38.70039 151.0378 3.170326 37.47573 151.0378 2.438743 39.31753 155.9738 -1.103744 39.31754 145.874 -1.103744 37.47573 151.6167 -1.103744 38.70039 146.3776 -1.103744 37.47573 144.4816 -1.103744 39.31753 155.9738 -6.925808 39.31754 150.5315 -6.925808 39.31754 146.8221 -7.789066 39.31754 146.6534 -7.789066 39.31754 152.7816 -1.103744 39.31754 152.2433 -3.941509 39.31754 152.1198 -4.518203 39.31753 155.0093 -1.103744 39.31753 155.0093 -5.800818 39.31754 145.0054 -7.219635 39.31754 145.5043 -6.633163 39.31754 146.1679 -5.751793 39.31754 145.8813 -7.281515 39.31754 153.9384 -6.269903 39.31753 155.0093 -5.613442 39.31754 151.6906 -6.511564 39.31754 151.1949 -1.103744 39.31754 144.9852 -6.436628 38.70039 149.8702 -6.436628 37.47573 149.8702 -6.436628 37.47573 146.9177 -6.43663 38.70039 146.9177 -8.278248 38.70039 153.8347 -8.278248 38.70039 146.5578 -8.278248 37.47573 146.5578 -8.278248 37.47573 153.8347 -4.775733 38.70043 156.9494 -4.775733 37.47573 156.9494 -1.103744 38.70039 151.6167 -3.806212 37.47573 151.5133 -3.806212 38.70039 151.5133 -5.8286 38.70039 144.5091 -5.8286 37.47573 144.5091 -7.551968 37.47573 145.1282 -7.551968 38.70039 145.1282 -6.300829 38.70039 146.544 -6.300829 37.47573 146.544 -5.724011 37.47573 146.3776 -5.724011 38.70039 146.3776 -8.461815 38.70043 156.9494 -8.461815 37.47573 156.9494 -8.461815 38.70043 155.0093 -8.461815 37.47573 155.0093 -8.461815 37.47573 155.9738 -8.461815 39.31753 155.9738 -7.600338 38.70042 155.0093 -7.600338 37.47573 155.0093 -6.134699 38.70039 150.4831 -6.134699 37.47573 150.4831 -1.103744 38.70039 144.4816 -5.377813 37.47573 151.0378 -5.377813 38.70039 151.0378 -4.64623 39.31753 155.9738 10.9723 41.53192 173.8982 10.9723 39.45044 176.007 10.9723 41.53192 164.6898 10.9723 41.53192 169.2228 38.53815 35.26818 129.6871 37.71501 37.73759 129.6871 35.2456 38.56072 129.6871 36.47788 39.45044 176.007 38.4318 39.0051 176.007 38.87714 37.05117 176.007 35.451 39.63248 130.6999 36.81567 41.53192 164.6898 39.59397 35.48951 130.6999 40.95864 37.38895 164.6898 36.81566 41.53192 173.8982 40.95863 37.38895 173.8982 38.55823 38.59674 130.6999 39.9229 40.49618 164.6898 39.92289 40.49618 173.8982 36.73121 41.01155 175.4798 40.43826 37.30451 175.4798 39.55012 40.12341 175.4798 36.13555 25.83975 129.6871 36.13554 5.731884 129.6871 38.53815 25.83975 129.6871 39.59397 25.83975 130.6999 40.6981 25.83975 158.2004 38.53815 5.731884 129.6871 39.59397 5.731883 130.6999 40.6981 5.731882 158.2004 40.76041 7.284054 159.7526 40.76041 24.28758 159.7526 40.74483 25.4517 159.3645 40.74483 6.119925 159.3645 36.13555 5.731883 158.2004 36.13555 6.119926 159.3645 36.13555 7.284054 159.7526 36.13555 25.83975 158.2004 36.13555 25.4517 159.3645 36.13555 24.28758 159.7526 15.68362 36.31864 129.6871 30.45106 36.31864 129.6871 15.68362 38.56072 129.6871 15.68362 39.63248 130.6999 15.68362 41.16928 158.2004 30.45106 38.56072 129.6871 30.45106 39.63248 130.6999 30.45106 41.16928 158.2004 28.89889 41.25602 159.7526 17.23579 41.25602 159.7526 16.07166 41.23434 159.3645 30.06302 41.23434 159.3645 28.89889 36.31864 159.7526 30.06302 36.31864 159.3645 30.45106 36.31864 158.2004 15.68362 36.31865 158.2004 16.07166 36.31865 159.3645 17.23579 36.31865 159.7526 37.63675 5.731886 176.007 37.63675 25.83975 176.007 40.95863 25.83975 173.8982 40.43826 25.83975 175.4798 38.87714 25.83975 176.007 40.95864 25.83975 170.3869 40.95863 5.731886 173.8982 40.95864 5.731886 170.3869 40.43826 5.731886 175.4798 38.87714 5.731886 176.007 40.95864 24.28758 168.8348 40.95864 7.284057 168.8348 40.95864 25.4517 169.2228 40.95864 6.119928 169.2228 37.63675 5.731886 170.3869 37.63675 6.119929 169.2228 37.63675 7.284058 168.8348 37.63675 24.28758 168.8348 37.63675 25.45171 169.2228 37.63675 25.83975 170.3869 30.45106 38.14337 176.007 15.68362 38.14337 176.007 15.68362 39.45044 176.007 15.68362 41.53192 173.8982 15.68362 41.01155 175.4798 15.68362 41.53192 170.3869 30.45106 41.01155 175.4798 30.45106 41.53192 173.8982 30.45106 41.53192 170.3869 30.45106 39.45044 176.007 17.23579 41.53192 168.8348 28.89889 41.53192 168.8348 16.07166 41.53192 169.2228 30.06302 41.53192 169.2228 28.89889 38.14337 168.8348 30.06302 38.14337 169.2228 17.23579 38.14337 168.8348 16.07166 38.14337 169.2228 15.68362 38.14337 170.3869 30.45106 38.14337 170.3869 40.95864 7.312862 164.6898 40.95864 24.281 164.6898 40.95864 25.4423 164.6898 40.95864 6.15367 164.6898 40.95864 37.38895 170.3869 39.92289 40.49618 170.3869 36.81566 41.53192 170.3869 40.95864 37.38895 169.2228 39.92289 40.49618 169.2228 36.81566 41.53192 169.2228 28.97054 41.53192 164.6898 30.14089 41.53192 164.6898 36.60186 41.23434 159.3645 39.70909 40.1986 159.3645 40.74483 37.09137 159.3645 40.6981 37.02631 158.2004 39.66235 40.13354 158.2004 36.55513 41.16928 158.2004 17.30745 41.53192 164.6898 16.14953 41.53192 164.6898 23.04834 38.70043 156.9494 23.04834 37.47573 156.9494 23.04834 37.47573 146.3776 17.22628 39.31754 150.5315 16.36302 39.31754 152.7816 16.36302 39.31754 146.6534 17.22628 39.31754 146.8221 19.63388 39.31753 155.0093 20.21058 39.31754 152.1198 18.35127 39.31754 145.0054 18.40029 39.31754 145.8813 17.51892 39.31754 146.1679 16.93245 39.31754 145.5043 16.87057 39.31754 153.9384 17.64052 39.31754 151.1949 18.53864 39.31754 151.6906 17.88218 39.31753 155.0093 17.71546 38.70039 149.8702 17.71545 38.70039 146.9177 17.71546 37.47573 146.9177 17.71546 37.47573 149.8702 15.87384 38.70039 153.8347 15.87384 37.47573 153.8347 15.87384 37.47573 146.5578 15.87384 38.70039 146.5578 19.37635 38.70043 156.9494 19.37635 37.47573 156.9494 20.34587 38.70039 151.5133 20.34587 37.47573 151.5133 18.32348 38.70039 144.5091 16.60012 38.70039 145.1282 16.60012 37.47573 145.1282 18.32348 37.47573 144.5091 17.85126 38.70039 146.544 18.42807 38.70039 146.3776 18.42807 37.47573 146.3776 17.85126 37.47573 146.544 15.69027 38.70043 156.9494 15.69027 37.47573 156.9494 15.69027 38.70043 155.0093 15.69027 39.31753 155.9738 15.69027 37.47573 155.9738 15.69027 37.47573 155.0093 16.55175 38.70042 155.0093 16.55175 37.47573 155.0093 18.01739 38.70039 150.4831 18.01739 37.47573 150.4831 18.77427 38.70039 151.0378 18.77427 37.47573 151.0378 19.50586 39.31753 155.9738 23.04834 39.31754 145.874 23.04834 37.47573 151.6167 23.04834 38.70039 146.3776 23.04834 37.47573 144.4816 23.04834 39.31753 155.9738 28.87041 39.31754 150.5315 28.87041 39.31754 146.8221 29.73366 39.31754 146.6534 29.73366 39.31754 152.7816 23.04834 39.31754 152.2433 25.88611 39.31754 152.1198 26.4628 39.31753 155.0093 23.04834 39.31753 155.0093 27.74542 39.31754 145.0054 29.16423 39.31754 145.5043 28.57776 39.31754 146.1679 27.69639 39.31754 145.8813 29.22611 39.31754 153.9384 28.2145 39.31753 155.0093 27.55804 39.31754 151.6906 28.45616 39.31754 151.1949 23.04834 39.31754 144.9852 28.38123 38.70039 149.8702 28.38123 37.47573 149.8702 28.38123 37.47573 146.9177 28.38123 38.70039 146.9177 30.22285 38.70039 153.8347 30.22285 38.70039 146.5578 30.22285 37.47573 146.5578 30.22285 37.47573 153.8347 26.72033 38.70043 156.9494 26.72033 37.47573 156.9494 23.04834 38.70039 151.6167 25.75081 37.47573 151.5133 25.75081 38.70039 151.5133 27.7732 38.70039 144.5091 27.7732 37.47573 144.5091 29.49657 37.47573 145.1282 29.49657 38.70039 145.1282 28.24543 38.70039 146.544 28.24543 37.47573 146.544 27.66861 37.47573 146.3776 27.66861 38.70039 146.3776 30.40641 38.70043 156.9494 30.40641 37.47573 156.9494 30.40641 38.70043 155.0093 30.40641 37.47573 155.0093 30.40641 37.47573 155.9738 30.40641 39.31753 155.9738 29.54494 38.70042 155.0093 29.54494 37.47573 155.0093 28.0793 38.70039 150.4831 28.0793 37.47573 150.4831 23.04834 38.70039 144.4816 27.32241 37.47573 151.0378 27.32241 38.70039 151.0378 26.59083 39.31753 155.9738 -37.35448 -28.4024 157.2454 -37.35448 -31.58863 153.2378 -37.35448 -29.80026 130.1495 -37.35448 -29.31087 129.6872 -37.35448 -31.58863 149.873 -37.35448 0 157.2454 -37.35448 -29.42375 153.5353 -37.35448 -30.78969 147.8021 -37.35448 -30.90577 149.873 -53.00191 0 157.2454 -52.35549 0 130.1504 -53.10922 0 147.3571 -56.17117 0 149.873 -56.17117 0 153.2378 -55.44563 0 149.873 -54.0526 0 153.5353 -51.86 0 129.6871 -55.3561 0 147.8021 -52.81626 -28.21675 157.2454 -52.25931 -28.4024 157.2454 -53.00191 -27.6598 157.2454 -52.35549 -4.752643 130.1504 -53.10922 -3.079486 147.3571 -56.17117 -30.84603 149.873 -56.17117 -30.84603 153.2378 -55.44563 -30.16317 149.873 -53.31 -29.42375 153.5353 -55.42857 -31.58863 153.2378 -41.01063 -29.42375 153.5353 -48.92695 -29.42375 153.5353 -54.05259 -28.68115 153.5353 -53.35078 -29.31087 129.6872 -53.83423 -29.80026 130.1495 -54.61351 -30.78969 147.8021 -54.70303 -30.90577 149.873 -55.35611 -20.51354 147.8021 -54.57683 -22.25408 130.1495 -54.57683 -29.05766 130.1495 -55.35611 -30.04709 147.8021 -53.10924 -13.96375 147.3573 -52.35374 -12.26866 130.1486 -52.35374 -21.75667 130.1486 -53.10924 -20.06158 147.3573 -55.35611 -3.532016 147.8021 -54.57683 -5.250237 130.1495 -54.57683 -11.77126 130.1495 -55.3561 -13.51179 147.8021 -54.09337 -22.30204 129.6872 -54.09337 -28.56827 129.6872 -51.86001 -12.23048 129.6873 -51.86001 -21.79485 129.6873 -54.09337 -5.291624 129.6872 -54.09337 -11.72329 129.6872 -51.86 -4.799234 129.6871 -55.42857 -31.58863 149.873 -41.01063 -26.99314 153.5353 -41.52228 -26.99314 155.817 -48.39953 -26.99314 155.817 -48.92695 -26.99314 153.5353 -48.39953 -28.79562 155.817 -41.52228 -28.79562 155.817 -55.17046 -30.60404 147.8021 -55.25998 -30.72012 149.873 -55.98553 -31.40298 153.2378 -55.98553 -31.40298 149.873 -53.86694 -29.2381 153.5353 -54.39118 -29.61461 130.1495 -53.90773 -29.12522 129.6872 -21.70705 0 157.2454 -22.35346 0 130.1504 -21.59973 0 147.3571 -18.53778 0 149.873 -18.53778 0 153.2378 -19.26332 0 149.873 -20.65636 0 153.5353 -22.84895 0 129.6871 -19.35285 0 147.8021 -21.8927 -28.21675 157.2454 -22.44964 -28.4024 157.2454 -21.70705 -27.6598 157.2454 -22.35346 -4.752643 130.1504 -21.59973 -3.079486 147.3571 -18.53778 -30.84603 149.873 -18.53778 -30.84603 153.2378 -19.26332 -30.16317 149.873 -21.39895 -29.42375 153.5353 -19.28038 -31.58863 153.2378 -33.69832 -29.42375 153.5353 -25.782 -29.42375 153.5353 -20.65636 -28.68115 153.5353 -21.35818 -29.31087 129.6872 -20.87472 -29.80026 130.1495 -20.09544 -30.78969 147.8021 -20.00592 -30.90577 149.873 -19.35284 -20.51354 147.8021 -20.13212 -22.25408 130.1495 -20.13212 -29.05766 130.1495 -19.35284 -30.04709 147.8021 -21.59972 -13.96375 147.3573 -22.35522 -12.26866 130.1486 -22.35522 -21.75667 130.1486 -21.59972 -20.06158 147.3573 -19.35284 -3.532016 147.8021 -20.13212 -5.250237 130.1495 -20.13212 -11.77126 130.1495 -19.35285 -13.51179 147.8021 -20.61558 -22.30204 129.6872 -20.61558 -28.56827 129.6872 -22.84894 -12.23048 129.6873 -22.84894 -21.79485 129.6873 -20.61558 -5.291624 129.6872 -20.61558 -11.72329 129.6872 -22.84895 -4.799234 129.6871 -19.28038 -31.58863 149.873 -33.69832 -26.99314 153.5353 -33.18667 -26.99314 155.817 -26.30943 -26.99314 155.817 -25.782 -26.99314 153.5353 -26.30943 -28.79562 155.817 -33.18667 -28.79562 155.817 -19.53849 -30.60404 147.8021 -19.44898 -30.72012 149.873 -18.72343 -31.40298 153.2378 -18.72343 -31.40298 149.873 -20.84201 -29.2381 153.5353 -20.31777 -29.61461 130.1495 -20.80123 -29.12522 129.6872 -37.35448 28.4024 157.2454 -37.35448 31.58863 153.2378 -37.35448 29.80026 130.1495 -37.35448 29.31087 129.6872 -37.35448 31.58863 149.873 -37.35448 29.42375 153.5353 -37.35448 30.78969 147.8021 -37.35448 30.90577 149.873 -52.81626 28.21675 157.2454 -52.25931 28.4024 157.2454 -53.00191 27.6598 157.2454 -52.35549 4.752643 130.1504 -53.10922 3.079486 147.3571 -56.17117 30.84603 149.873 -56.17117 30.84603 153.2378 -55.44563 30.16317 149.873 -53.31 29.42375 153.5353 -55.42857 31.58863 153.2378 -41.01063 29.42375 153.5353 -48.92695 29.42375 153.5353 -54.05259 28.68115 153.5353 -53.35078 29.31087 129.6872 -53.83423 29.80026 130.1495 -54.61351 30.78969 147.8021 -54.70303 30.90577 149.873 -55.35611 20.51354 147.8021 -54.57683 22.25408 130.1495 -54.57683 29.05766 130.1495 -55.35611 30.04709 147.8021 -53.10924 13.96375 147.3573 -52.35374 12.26866 130.1486 -52.35374 21.75667 130.1486 -53.10924 20.06158 147.3573 -55.35611 3.532016 147.8021 -54.57683 5.250237 130.1495 -54.57683 11.77126 130.1495 -55.3561 13.51179 147.8021 -54.09337 22.30204 129.6872 -54.09337 28.56827 129.6872 -51.86001 12.23048 129.6873 -51.86001 21.79485 129.6873 -54.09337 5.291624 129.6872 -54.09337 11.72329 129.6872 -51.86 4.799234 129.6871 -55.42857 31.58863 149.873 -41.01063 26.99314 153.5353 -41.52228 26.99314 155.817 -48.39953 26.99314 155.817 -48.92695 26.99314 153.5353 -48.39953 28.79562 155.817 -41.52228 28.79562 155.817 -55.17046 30.60404 147.8021 -55.25998 30.72012 149.873 -55.98553 31.40298 153.2378 -55.98553 31.40298 149.873 -53.86694 29.2381 153.5353 -54.39118 29.61461 130.1495 -53.90773 29.12522 129.6872 -21.8927 28.21675 157.2454 -22.44964 28.4024 157.2454 -21.70705 27.6598 157.2454 -22.35346 4.752643 130.1504 -21.59973 3.079486 147.3571 -18.53778 30.84603 149.873 -18.53778 30.84603 153.2378 -19.26332 30.16317 149.873 -21.39895 29.42375 153.5353 -19.28038 31.58863 153.2378 -33.69832 29.42375 153.5353 -25.782 29.42375 153.5353 -20.65636 28.68115 153.5353 -21.35818 29.31087 129.6872 -20.87472 29.80026 130.1495 -20.09544 30.78969 147.8021 -20.00592 30.90577 149.873 -19.35284 20.51354 147.8021 -20.13212 22.25408 130.1495 -20.13212 29.05766 130.1495 -19.35284 30.04709 147.8021 -21.59972 13.96375 147.3573 -22.35522 12.26866 130.1486 -22.35522 21.75667 130.1486 -21.59972 20.06158 147.3573 -19.35284 3.532016 147.8021 -20.13212 5.250237 130.1495 -20.13212 11.77126 130.1495 -19.35285 13.51179 147.8021 -20.61558 22.30204 129.6872 -20.61558 28.56827 129.6872 -22.84894 12.23048 129.6873 -22.84894 21.79485 129.6873 -20.61558 5.291624 129.6872 -20.61558 11.72329 129.6872 -22.84895 4.799234 129.6871 -19.28038 31.58863 149.873 -33.69832 26.99314 153.5353 -33.18667 26.99314 155.817 -26.30943 26.99314 155.817 -25.782 26.99314 153.5353 -26.30943 28.79562 155.817 -33.18667 28.79562 155.817 -19.53849 30.60404 147.8021 -19.44898 30.72012 149.873 -18.72343 31.40298 153.2378 -18.72343 31.40298 149.873 -20.84201 29.2381 153.5353 -20.31777 29.61461 130.1495 -20.80123 29.12522 129.6872 + + +-16.593552 -35.268177 129.687149 +-15.770415 -37.737591 129.687149 +-13.301003 -38.560726 129.687149 +-14.533280 -39.450439 176.006958 +-16.487202 -39.005096 176.006958 +-16.932541 -37.051178 176.006958 +-13.506402 -39.632484 130.699921 +-14.871070 -41.531925 164.689804 +-17.649372 -35.489513 130.699921 +-19.014042 -37.388954 164.689804 +-14.871060 -41.531925 173.898239 +-19.014034 -37.388954 173.898239 +-16.613632 -38.596741 130.699921 +-17.978298 -40.496181 164.689804 +-17.978291 -40.496181 173.898239 +-14.786614 -41.011555 175.479782 +-18.493660 -37.304512 175.479782 +-17.605515 -40.123413 175.479782 +-14.190949 -25.839746 129.687149 +-14.190946 -5.731884 129.687149 +-16.593552 -25.839746 129.687149 +-17.649372 -25.839746 130.699921 +-18.753498 -25.839746 158.200409 +-16.593552 -5.731884 129.687149 +-17.649372 -5.731883 130.699921 +-18.753498 -5.731882 158.200424 +-18.815815 -7.284054 159.752594 +-18.815815 -24.287575 159.752594 +-18.800236 -25.451702 159.364548 +-18.800236 -6.119925 159.364548 +-14.190949 -5.731883 158.200424 +-14.190949 -6.119926 159.364548 +-14.190949 -7.284054 159.752594 +-14.190953 -25.839746 158.200409 +-14.190953 -25.451702 159.364548 +-14.190953 -24.287575 159.752594 +6.260983 -36.318645 129.687149 +-8.506461 -36.318645 129.687149 +6.260983 -38.560726 129.687149 +6.260983 -39.632484 130.699921 +6.260983 -41.169285 158.200409 +-8.506461 -38.560726 129.687149 +-8.506461 -39.632484 130.699921 +-8.506461 -41.169285 158.200409 +-6.954288 -41.256023 159.752594 +4.708812 -41.256023 159.752594 +5.872939 -41.234337 159.364548 +-8.118417 -41.234337 159.364548 +-6.954288 -36.318645 159.752594 +-8.118417 -36.318645 159.364548 +-8.506461 -36.318645 158.200409 +6.260983 -36.318649 158.200409 +5.872940 -36.318649 159.364548 +4.708813 -36.318649 159.752594 +-15.692151 -5.731886 176.006958 +-15.692155 -25.839748 176.006958 +-19.014034 -25.839746 173.898239 +-18.493660 -25.839746 175.479782 +-16.932541 -25.839748 176.006958 +-19.014038 -25.839746 170.386932 +-19.014034 -5.731886 173.898239 +-19.014038 -5.731886 170.386948 +-18.493660 -5.731886 175.479782 +-16.932541 -5.731886 176.006958 +-19.014038 -24.287575 168.834763 +-19.014038 -7.284057 168.834763 +-19.014038 -25.451704 169.222809 +-19.014038 -6.119928 169.222809 +-15.692151 -5.731886 170.386932 +-15.692151 -6.119929 169.222809 +-15.692151 -7.284058 168.834763 +-15.692155 -24.287577 168.834763 +-15.692155 -25.451706 169.222809 +-15.692155 -25.839748 170.386932 +-8.506461 -38.143372 176.006958 +6.260980 -38.143368 176.006958 +6.260980 -39.450439 176.006958 +6.260979 -41.531925 173.898239 +6.260979 -41.011555 175.479782 +6.260979 -41.531925 170.386948 +-8.506461 -41.011555 175.479782 +-8.506461 -41.531925 173.898239 +-8.506461 -41.531925 170.386932 +-8.506461 -39.450439 176.006958 +4.708809 -41.531925 168.834763 +-6.954289 -41.531925 168.834763 +5.872936 -41.531925 169.222809 +-8.118417 -41.531925 169.222809 +-6.954289 -38.143372 168.834763 +-8.118417 -38.143372 169.222809 +4.708809 -38.143375 168.834763 +5.872936 -38.143368 169.222809 +6.260980 -38.143368 170.386932 +-8.506461 -38.143372 170.386932 +-19.014042 -7.312862 164.689804 +-19.014042 -24.280998 164.689804 +-19.014042 -25.442301 164.689804 +-19.014042 -6.153670 164.689804 +-19.014038 -37.388954 170.386932 +-17.978294 -40.496181 170.386932 +-14.871062 -41.531925 170.386932 +-19.014038 -37.388954 169.222809 +-17.978294 -40.496181 169.222809 +-14.871064 -41.531925 169.222809 +-7.025945 -41.531925 164.689804 +-8.196286 -41.531925 164.689804 +-14.657264 -41.234337 159.364548 +-17.764492 -40.198597 159.364548 +-18.800236 -37.091366 159.364548 +-18.753498 -37.026314 158.200409 +-17.717754 -40.133545 158.200409 +-14.610526 -41.169281 158.200409 +4.637154 -41.531925 164.689804 +5.795068 -41.531925 164.689804 +10.972301 -41.169273 158.200394 +10.972301 -37.032719 176.006958 +-16.932541 0.000000 176.006958 +10.972301 -38.560726 129.687149 +10.972301 -39.632484 130.699921 +10.972301 -41.011555 175.479782 +10.972301 -41.234375 159.364563 +10.972301 -41.531925 170.386948 +-18.493660 0.000000 175.479782 +-19.014038 0.000000 169.222778 +-8.461814 -38.700436 156.949387 +-8.461814 -38.700436 155.009293 +-8.461814 -39.317528 155.973785 +-8.461814 -37.475731 155.973785 +-1.103743 -38.700436 156.949387 +-1.103743 -37.475731 156.949387 +-1.103743 -37.475731 146.377563 +4.718322 -39.317539 150.531494 +5.581581 -39.317539 152.781586 +5.581581 -39.317539 146.653397 +4.718322 -39.317539 146.822098 +2.310718 -39.317528 155.009293 +1.734024 -39.317539 152.119827 +3.593332 -39.317539 145.005432 +3.544307 -39.317539 145.881287 +4.425677 -39.317539 146.167908 +5.012148 -39.317539 145.504303 +5.074028 -39.317539 153.938354 +4.304079 -39.317539 151.194901 +3.405956 -39.317539 151.690582 +4.062416 -39.317528 155.009293 +4.229142 -38.700390 149.870178 +4.229143 -38.700390 146.917694 +4.229142 -37.475731 146.917694 +4.229142 -37.475731 149.870178 +6.070762 -38.700390 153.834656 +6.070762 -37.475731 153.834656 +6.070762 -37.475731 146.557800 +6.070762 -38.700390 146.557800 +2.568247 -38.700436 156.949387 +2.568247 -37.475731 156.949387 +1.598726 -38.700390 151.513321 +1.598726 -37.475731 151.513321 +3.621114 -38.700390 144.509125 +5.344482 -38.700390 145.128250 +5.344482 -37.475731 145.128250 +3.621114 -37.475731 144.509125 +4.093343 -38.700390 146.543961 +3.516525 -38.700390 146.377594 +3.516525 -37.475731 146.377594 +4.093343 -37.475731 146.543961 +6.254330 -38.700436 156.949387 +6.254330 -37.475731 156.949387 +6.254330 -38.700436 155.009293 +6.254330 -39.317528 155.973785 +6.254330 -37.475731 155.973785 +6.254330 -37.475731 155.009293 +5.392851 -38.700424 155.009293 +5.392851 -37.475731 155.009293 +3.927212 -38.700390 150.483063 +3.927212 -37.475731 150.483063 +3.170327 -38.700390 151.037842 +3.170327 -37.475731 151.037842 +2.438744 -39.317528 155.973785 +-1.103743 -39.317539 145.873962 +-1.103743 -37.475731 151.616714 +-1.103743 -38.700390 146.377563 +-1.103743 -37.475731 144.481644 +-1.103743 -39.317528 155.973785 +-6.925807 -39.317539 150.531494 +-6.925807 -39.317539 146.822098 +-7.789065 -39.317539 146.653397 +-7.789065 -39.317539 152.781586 +-1.103743 -39.317539 152.243317 +-3.941508 -39.317539 152.119827 +-4.518202 -39.317528 155.009293 +-1.103743 -39.317528 155.009293 +-5.800817 -39.317539 145.005432 +-7.219634 -39.317539 145.504303 +-6.633162 -39.317539 146.167908 +-5.751792 -39.317539 145.881287 +-7.281514 -39.317539 153.938354 +-6.269902 -39.317528 155.009293 +-5.613441 -39.317539 151.690582 +-6.511563 -39.317539 151.194901 +-1.103743 -39.317539 144.985245 +-6.436627 -38.700390 149.870178 +-6.436627 -37.475731 149.870178 +-6.436627 -37.475731 146.917694 +-6.436629 -38.700390 146.917694 +-8.278247 -38.700390 153.834656 +-8.278247 -38.700390 146.557800 +-8.278247 -37.475731 146.557800 +-8.278247 -37.475731 153.834656 +-4.775732 -38.700436 156.949387 +-4.775732 -37.475731 156.949387 +-1.103743 -38.700390 151.616714 +-3.806211 -37.475731 151.513321 +-3.806211 -38.700390 151.513321 +-5.828599 -38.700390 144.509125 +-5.828599 -37.475731 144.509125 +-7.551967 -37.475731 145.128250 +-7.551967 -38.700390 145.128250 +-6.300828 -38.700390 146.543961 +-6.300828 -37.475731 146.543961 +-5.724010 -37.475731 146.377594 +-5.724010 -38.700390 146.377594 +-8.461814 -38.700436 156.949387 +-8.461814 -37.475731 156.949387 +-8.461814 -38.700436 155.009293 +-8.461814 -37.475731 155.009293 +-8.461814 -37.475731 155.973785 +-8.461814 -39.317528 155.973785 +-7.600337 -38.700424 155.009293 +-7.600337 -37.475731 155.009293 +-6.134698 -38.700390 150.483063 +-6.134698 -37.475731 150.483063 +-1.103743 -38.700390 144.481644 +-5.377812 -37.475731 151.037842 +-5.377812 -38.700390 151.037842 +-4.646229 -39.317528 155.973785 +36.555126 -41.169281 158.200409 +36.601864 -41.234337 159.364548 +39.709095 -40.198597 159.364548 +39.662357 -40.133545 158.200409 +40.958633 -37.388954 173.898239 +40.958637 -37.388954 170.386932 +39.922894 -40.496181 170.386932 +39.922890 -40.496181 173.898239 +40.744839 -37.091366 159.364548 +40.698097 -37.026314 158.200409 +36.815662 -41.531925 170.386932 +36.815662 -41.531925 173.898239 +36.731216 -41.011555 175.479782 +36.477882 -39.450439 176.006958 +38.431801 -39.005096 176.006958 +39.550117 -40.123413 175.479782 +38.877144 -37.051178 176.006958 +40.438259 -37.304512 175.479782 +39.593975 -35.489513 130.699921 +38.538155 -35.268177 129.687149 +37.715015 -37.737591 129.687149 +38.558231 -38.596741 130.699921 +35.245605 -38.560726 129.687149 +35.451004 -39.632484 130.699921 +39.593975 -25.839746 130.699921 +38.538155 -25.839746 129.687149 +39.593975 -5.731883 130.699921 +39.593975 0.000000 130.699921 +38.538155 -5.731884 129.687149 +36.135555 -25.839746 158.200409 +36.135551 -25.839746 129.687149 +40.698097 -25.839746 158.200409 +40.744839 -25.451702 159.364548 +36.135555 -25.451702 159.364548 +40.760418 -24.287575 159.752594 +36.135555 -24.287575 159.752594 +40.760418 -7.284054 159.752594 +36.135551 -7.284054 159.752594 +40.744839 -6.119925 159.364548 +36.135551 -6.119926 159.364548 +40.698097 -5.731882 158.200424 +36.135551 -5.731883 158.200424 +15.683619 -39.632484 130.699921 +15.683619 -38.560726 129.687149 +30.451061 -39.632484 130.699921 +30.451061 -38.560726 129.687149 +28.898888 -36.318645 159.752594 +28.898888 -41.256023 159.752594 +30.063019 -41.234337 159.364548 +30.063019 -36.318645 159.364548 +30.451061 -41.169285 158.200409 +30.451061 -36.318645 158.200409 +15.683618 -36.318649 158.200409 +15.683618 -36.318645 129.687149 +15.683619 -41.169285 158.200409 +16.071663 -41.234337 159.364548 +16.071661 -36.318649 159.364548 +17.235790 -41.256023 159.752594 +17.235788 -36.318649 159.752594 +40.958633 -25.839746 173.898239 +40.438259 -25.839746 175.479782 +38.877144 -25.839748 176.006958 +40.438259 -5.731886 175.479782 +38.877144 -5.731886 176.006958 +38.877140 0.000000 176.006958 +37.636753 -6.119929 169.222809 +37.636753 -5.731886 170.386932 +40.958637 -5.731886 170.386948 +40.958637 -6.119928 169.222809 +40.958637 -7.284057 168.834763 +37.636753 -7.284058 168.834763 +40.958637 -24.287575 168.834763 +37.636757 -24.287577 168.834763 +40.958637 -25.451704 169.222809 +37.636757 -25.451706 169.222809 +40.958637 -25.839746 170.386932 +37.636757 -25.839748 170.386932 +15.683622 -41.531925 173.898239 +10.972301 -41.531925 173.898239 +15.683622 -41.011555 175.479782 +10.972301 -39.450439 176.006958 +15.683621 -39.450439 176.006958 +30.451061 -41.531925 173.898239 +30.451061 -41.011555 175.479782 +30.451061 -39.450439 176.006958 +28.898891 -41.531925 168.834763 +28.898891 -38.143372 168.834763 +30.063019 -38.143372 169.222809 +30.063019 -41.531925 169.222809 +17.235792 -38.143375 168.834763 +17.235792 -41.531925 168.834763 +16.071665 -41.531925 169.222809 +16.071665 -38.143368 169.222809 +15.683621 -38.143368 170.386932 +15.683622 -41.531925 170.386948 +30.451061 -38.143372 170.386932 +30.451061 -41.531925 170.386932 +40.698128 0.000000 158.200394 +36.135548 -5.731884 129.687149 +28.970547 -41.531925 164.689804 +30.140888 -41.531925 164.689804 +30.451061 -36.318645 129.687149 +40.958641 -6.153670 164.689804 +37.636753 -5.731886 176.006958 +40.958633 -5.731886 173.898239 +37.636757 -25.839748 176.006958 +15.683621 -38.143368 176.006958 +30.451061 -38.143372 176.006958 +40.958633 0.000000 173.898239 +40.958641 -24.280998 164.689804 +40.958641 -7.312862 164.689804 +40.958641 -25.442301 164.689804 +40.958637 -37.388954 169.222809 +39.922894 -40.496181 169.222809 +36.815666 -41.531925 169.222809 +40.958641 -37.388954 164.689804 +39.922901 -40.496181 164.689804 +36.815670 -41.531925 164.689804 +17.307447 -41.531925 164.689804 +10.972301 -41.531925 164.689804 +16.149532 -41.531925 164.689804 +10.972301 -41.531925 169.222778 +30.406414 -38.700436 155.009293 +30.406414 -39.317528 155.973785 +30.406414 -37.475731 155.973785 +30.406414 -37.475731 155.009293 +30.406414 -38.700436 156.949387 +30.406414 -37.475731 156.949387 +17.226278 -39.317539 150.531494 +17.226278 -39.317539 146.822098 +16.363020 -39.317539 146.653397 +16.363020 -39.317539 152.781586 +23.048344 -39.317539 152.243317 +20.210577 -39.317539 152.119827 +19.633884 -39.317528 155.009293 +23.048344 -39.317528 155.009293 +18.351269 -39.317539 145.005432 +16.932453 -39.317539 145.504303 +17.518925 -39.317539 146.167908 +18.400295 -39.317539 145.881287 +16.870573 -39.317539 153.938354 +17.882185 -39.317528 155.009293 +18.538645 -39.317539 151.690582 +17.640522 -39.317539 151.194901 +23.048344 -39.317539 144.985245 +23.048344 -39.317539 145.873962 +17.715460 -38.700390 149.870178 +17.715460 -37.475731 149.870178 +17.715460 -37.475731 146.917694 +17.715458 -38.700390 146.917694 +15.873839 -38.700390 153.834656 +15.873839 -38.700390 146.557800 +15.873839 -37.475731 146.557800 +15.873839 -37.475731 153.834656 +19.376354 -38.700436 156.949387 +19.376354 -37.475731 156.949387 +23.048344 -37.475731 156.949387 +23.048344 -38.700436 156.949387 +23.048344 -38.700390 151.616714 +23.048344 -37.475731 151.616714 +20.345875 -37.475731 151.513321 +20.345875 -38.700390 151.513321 +18.323486 -38.700390 144.509125 +18.323486 -37.475731 144.509125 +16.600119 -37.475731 145.128250 +16.600119 -38.700390 145.128250 +17.851257 -38.700390 146.543961 +17.851257 -37.475731 146.543961 +18.428076 -37.475731 146.377594 +18.428076 -38.700390 146.377594 +15.690271 -38.700436 156.949387 +15.690271 -37.475731 156.949387 +15.690271 -38.700436 155.009293 +15.690271 -37.475731 155.009293 +15.690271 -37.475731 155.973785 +15.690271 -39.317528 155.973785 +16.551750 -38.700424 155.009293 +16.551750 -37.475731 155.009293 +18.017389 -38.700390 150.483063 +18.017389 -37.475731 150.483063 +23.048344 -37.475731 146.377563 +23.048344 -38.700390 146.377563 +23.048344 -38.700390 144.481644 +23.048344 -37.475731 144.481644 +18.774273 -37.475731 151.037842 +18.774273 -38.700390 151.037842 +19.505857 -39.317528 155.973785 +23.048344 -39.317528 155.973785 +28.870407 -39.317539 150.531494 +29.733665 -39.317539 152.781586 +29.733665 -39.317539 146.653397 +28.870407 -39.317539 146.822098 +26.462803 -39.317528 155.009293 +25.886108 -39.317539 152.119827 +27.745419 -39.317539 145.005432 +27.696392 -39.317539 145.881287 +28.577763 -39.317539 146.167908 +29.164234 -39.317539 145.504303 +29.226116 -39.317539 153.938354 +28.456165 -39.317539 151.194901 +27.558041 -39.317539 151.690582 +28.214504 -39.317528 155.009293 +28.381229 -38.700390 149.870178 +28.381229 -38.700390 146.917694 +28.381229 -37.475731 146.917694 +28.381229 -37.475731 149.870178 +30.222847 -38.700390 153.834656 +30.222847 -37.475731 153.834656 +30.222847 -37.475731 146.557800 +30.222847 -38.700390 146.557800 +26.720333 -38.700436 156.949387 +26.720333 -37.475731 156.949387 +25.750813 -38.700390 151.513321 +25.750813 -37.475731 151.513321 +27.773201 -38.700390 144.509125 +29.496567 -38.700390 145.128250 +29.496567 -37.475731 145.128250 +27.773201 -37.475731 144.509125 +28.245430 -38.700390 146.543961 +27.668610 -38.700390 146.377594 +27.668610 -37.475731 146.377594 +28.245430 -37.475731 146.543961 +30.406414 -38.700436 156.949387 +30.406414 -38.700436 155.009293 +30.406414 -39.317528 155.973785 +30.406414 -37.475731 155.973785 +29.544937 -38.700424 155.009293 +29.544937 -37.475731 155.009293 +28.079300 -38.700390 150.483063 +28.079300 -37.475731 150.483063 +27.322414 -38.700390 151.037842 +27.322414 -37.475731 151.037842 +26.590830 -39.317528 155.973785 +-14.610526 41.169281 158.200409 +-14.657264 41.234337 159.364548 +-17.764492 40.198597 159.364548 +-17.717754 40.133545 158.200409 +-19.014034 37.388954 173.898239 +-19.014038 37.388954 170.386932 +-17.978294 40.496181 170.386932 +-17.978291 40.496181 173.898239 +-18.800236 37.091366 159.364548 +-18.753498 37.026314 158.200409 +-14.871062 41.531925 170.386932 +-14.871060 41.531925 173.898239 +-14.786614 41.011555 175.479782 +-14.533280 39.450439 176.006958 +-16.487202 39.005096 176.006958 +-17.605515 40.123413 175.479782 +-16.932541 37.051178 176.006958 +-18.493660 37.304512 175.479782 +-17.649372 35.489513 130.699921 +-16.593552 35.268177 129.687149 +-15.770415 37.737591 129.687149 +-16.613632 38.596741 130.699921 +-13.301003 38.560726 129.687149 +-13.506402 39.632484 130.699921 +-17.649372 25.839746 130.699921 +-16.593552 25.839746 129.687149 +-17.649372 5.731883 130.699921 +-17.649372 0.000000 130.699921 +-16.593552 0.000000 129.687149 +-16.593552 5.731884 129.687149 +-14.190953 25.839746 158.200409 +-14.190949 25.839746 129.687149 +-18.753498 25.839746 158.200409 +-18.800236 25.451702 159.364548 +-14.190953 25.451702 159.364548 +-18.815815 24.287575 159.752594 +-14.190953 24.287575 159.752594 +-18.815815 7.284054 159.752594 +-14.190949 7.284054 159.752594 +-18.800236 6.119925 159.364548 +-14.190949 6.119926 159.364548 +-18.753498 5.731882 158.200424 +-14.190949 5.731883 158.200424 +6.260983 39.632484 130.699921 +6.260983 38.560726 129.687149 +10.972301 38.560726 129.687149 +10.972301 39.632484 130.699921 +-8.506461 39.632484 130.699921 +-8.506461 38.560726 129.687149 +-6.954288 36.318645 159.752594 +-6.954288 41.256023 159.752594 +-8.118417 41.234337 159.364548 +-8.118417 36.318645 159.364548 +-8.506461 41.169285 158.200409 +-8.506461 36.318645 158.200409 +6.260983 36.318649 158.200409 +6.260983 36.318645 129.687149 +6.260983 41.169285 158.200409 +5.872939 41.234337 159.364548 +5.872940 36.318649 159.364548 +4.708812 41.256023 159.752594 +4.708813 36.318649 159.752594 +-19.014034 25.839746 173.898239 +-18.493660 25.839746 175.479782 +-16.932541 25.839748 176.006958 +-18.493660 5.731886 175.479782 +-16.932541 5.731886 176.006958 +-15.692151 6.119929 169.222809 +-15.692151 5.731886 170.386932 +-19.014038 5.731886 170.386948 +-19.014038 6.119928 169.222809 +-19.014038 7.284057 168.834763 +-15.692151 7.284058 168.834763 +-19.014038 24.287575 168.834763 +-15.692155 24.287577 168.834763 +-19.014038 25.451704 169.222809 +-15.692155 25.451706 169.222809 +-19.014038 25.839746 170.386932 +-15.692155 25.839748 170.386932 +6.260979 41.531925 173.898239 +10.972301 41.531925 173.898239 +10.972301 41.011555 175.479782 +6.260979 41.011555 175.479782 +10.972301 39.450439 176.006958 +6.260980 39.450439 176.006958 +-8.506461 41.531925 173.898239 +-8.506461 41.011555 175.479782 +-8.506461 39.450439 176.006958 +-6.954289 41.531925 168.834763 +-6.954289 38.143372 168.834763 +-8.118417 38.143372 169.222809 +-8.118417 41.531925 169.222809 +4.708809 38.143375 168.834763 +4.708809 41.531925 168.834763 +5.872936 41.531925 169.222809 +5.872936 38.143368 169.222809 +6.260980 38.143368 170.386932 +6.260979 41.531925 170.386948 +-8.506461 38.143372 170.386932 +-8.506461 41.531925 170.386932 +-18.753525 0.000000 158.200394 +-14.190946 5.731884 129.687149 +-7.025945 41.531925 164.689804 +-8.196286 41.531925 164.689804 +-8.506461 36.318645 129.687149 +-19.014042 0.000000 164.689804 +-19.014042 6.153670 164.689804 +-15.692151 5.731886 176.006958 +-19.014034 5.731886 173.898239 +-15.692155 25.839748 176.006958 +10.972301 0.000000 176.006958 +6.260980 38.143368 176.006958 +-8.506461 38.143372 176.006958 +-19.014034 0.000000 173.898239 +10.972301 37.032719 176.006958 +-19.014042 24.280998 164.689804 +-19.014042 7.312862 164.689804 +-19.014042 25.442301 164.689804 +-19.014038 0.000000 170.386948 +-18.800209 0.000000 159.364563 +-19.014038 37.388954 169.222809 +-17.978294 40.496181 169.222809 +-14.871064 41.531925 169.222809 +-19.014042 37.388954 164.689804 +-17.978298 40.496181 164.689804 +-14.871070 41.531925 164.689804 +4.637154 41.531925 164.689804 +10.972301 41.234375 159.364563 +10.972301 41.531925 164.689804 +5.795068 41.531925 164.689804 +10.972301 41.531925 170.386948 +10.972301 41.169273 158.200394 +10.972301 41.531925 169.222778 +-8.461814 38.700436 155.009293 +-8.461814 39.317528 155.973785 +-8.461814 37.475731 155.973785 +-8.461814 37.475731 155.009293 +-8.461814 38.700436 156.949387 +-8.461814 37.475731 156.949387 +4.718322 39.317539 150.531494 +4.718322 39.317539 146.822098 +5.581581 39.317539 146.653397 +5.581581 39.317539 152.781586 +-1.103743 39.317539 152.243317 +1.734024 39.317539 152.119827 +2.310718 39.317528 155.009293 +-1.103743 39.317528 155.009293 +3.593332 39.317539 145.005432 +5.012148 39.317539 145.504303 +4.425677 39.317539 146.167908 +3.544307 39.317539 145.881287 +5.074028 39.317539 153.938354 +4.062416 39.317528 155.009293 +3.405956 39.317539 151.690582 +4.304079 39.317539 151.194901 +-1.103743 39.317539 144.985245 +-1.103743 39.317539 145.873962 +4.229142 38.700390 149.870178 +4.229142 37.475731 149.870178 +4.229142 37.475731 146.917694 +4.229143 38.700390 146.917694 +6.070762 38.700390 153.834656 +6.070762 38.700390 146.557800 +6.070762 37.475731 146.557800 +6.070762 37.475731 153.834656 +2.568247 38.700436 156.949387 +2.568247 37.475731 156.949387 +-1.103743 37.475731 156.949387 +-1.103743 38.700436 156.949387 +-1.103743 38.700390 151.616714 +-1.103743 37.475731 151.616714 +1.598726 37.475731 151.513321 +1.598726 38.700390 151.513321 +3.621114 38.700390 144.509125 +3.621114 37.475731 144.509125 +5.344482 37.475731 145.128250 +5.344482 38.700390 145.128250 +4.093343 38.700390 146.543961 +4.093343 37.475731 146.543961 +3.516525 37.475731 146.377594 +3.516525 38.700390 146.377594 +6.254330 38.700436 156.949387 +6.254330 37.475731 156.949387 +6.254330 38.700436 155.009293 +6.254330 37.475731 155.009293 +6.254330 37.475731 155.973785 +6.254330 39.317528 155.973785 +5.392851 38.700424 155.009293 +5.392851 37.475731 155.009293 +3.927212 38.700390 150.483063 +3.927212 37.475731 150.483063 +-1.103743 37.475731 146.377563 +-1.103743 38.700390 146.377563 +-1.103743 38.700390 144.481644 +-1.103743 37.475731 144.481644 +3.170327 37.475731 151.037842 +3.170327 38.700390 151.037842 +2.438744 39.317528 155.973785 +-1.103743 39.317528 155.973785 +-6.925807 39.317539 150.531494 +-7.789065 39.317539 152.781586 +-7.789065 39.317539 146.653397 +-6.925807 39.317539 146.822098 +-4.518202 39.317528 155.009293 +-3.941508 39.317539 152.119827 +-5.800817 39.317539 145.005432 +-5.751792 39.317539 145.881287 +-6.633162 39.317539 146.167908 +-7.219634 39.317539 145.504303 +-7.281514 39.317539 153.938354 +-6.511563 39.317539 151.194901 +-5.613441 39.317539 151.690582 +-6.269902 39.317528 155.009293 +-6.436627 38.700390 149.870178 +-6.436629 38.700390 146.917694 +-6.436627 37.475731 146.917694 +-6.436627 37.475731 149.870178 +-8.278247 38.700390 153.834656 +-8.278247 37.475731 153.834656 +-8.278247 37.475731 146.557800 +-8.278247 38.700390 146.557800 +-4.775732 38.700436 156.949387 +-4.775732 37.475731 156.949387 +-3.806211 38.700390 151.513321 +-3.806211 37.475731 151.513321 +-5.828599 38.700390 144.509125 +-7.551967 38.700390 145.128250 +-7.551967 37.475731 145.128250 +-5.828599 37.475731 144.509125 +-6.300828 38.700390 146.543961 +-5.724010 38.700390 146.377594 +-5.724010 37.475731 146.377594 +-6.300828 37.475731 146.543961 +-8.461814 38.700436 156.949387 +-8.461814 38.700436 155.009293 +-8.461814 39.317528 155.973785 +-8.461814 37.475731 155.973785 +-7.600337 38.700424 155.009293 +-7.600337 37.475731 155.009293 +-6.134698 38.700390 150.483063 +-6.134698 37.475731 150.483063 +-5.377812 38.700390 151.037842 +-5.377812 37.475731 151.037842 +-4.646229 39.317528 155.973785 +36.555126 41.169281 158.200409 +39.662357 40.133545 158.200409 +39.709095 40.198597 159.364548 +36.601864 41.234337 159.364548 +40.958633 37.388954 173.898239 +39.922890 40.496181 173.898239 +39.922894 40.496181 170.386932 +40.958637 37.388954 170.386932 +40.698097 37.026314 158.200409 +40.744839 37.091366 159.364548 +36.815662 41.531925 173.898239 +36.815662 41.531925 170.386932 +36.731216 41.011555 175.479782 +39.550117 40.123413 175.479782 +38.431801 39.005096 176.006958 +36.477882 39.450439 176.006958 +40.438259 37.304512 175.479782 +38.877144 37.051178 176.006958 +39.593975 35.489513 130.699921 +38.558231 38.596741 130.699921 +37.715015 37.737591 129.687149 +38.538155 35.268177 129.687149 +35.451004 39.632484 130.699921 +35.245605 38.560726 129.687149 +38.538155 25.839746 129.687149 +39.593975 25.839746 130.699921 +39.593975 5.731883 130.699921 +38.538155 5.731884 129.687149 +38.538155 0.000000 129.687149 +36.135555 25.839746 158.200409 +40.698097 25.839746 158.200409 +36.135551 25.839746 129.687149 +36.135555 25.451702 159.364548 +40.744839 25.451702 159.364548 +36.135555 24.287575 159.752594 +40.760418 24.287575 159.752594 +36.135551 7.284054 159.752594 +40.760418 7.284054 159.752594 +36.135551 6.119926 159.364548 +40.744839 6.119925 159.364548 +36.135551 5.731883 158.200424 +40.698097 5.731882 158.200424 +15.683619 39.632484 130.699921 +15.683619 38.560726 129.687149 +30.451061 39.632484 130.699921 +30.451061 38.560726 129.687149 +28.898888 36.318645 159.752594 +30.063019 36.318645 159.364548 +30.063019 41.234337 159.364548 +28.898888 41.256023 159.752594 +30.451061 36.318645 158.200409 +30.451061 41.169285 158.200409 +15.683618 36.318649 158.200409 +15.683619 41.169285 158.200409 +15.683618 36.318645 129.687149 +16.071661 36.318649 159.364548 +16.071663 41.234337 159.364548 +17.235788 36.318649 159.752594 +17.235790 41.256023 159.752594 +40.958633 25.839746 173.898239 +40.438259 25.839746 175.479782 +38.877144 25.839748 176.006958 +40.438259 5.731886 175.479782 +40.438259 0.000000 175.479782 +38.877144 5.731886 176.006958 +37.636753 6.119929 169.222809 +40.958637 6.119928 169.222809 +40.958637 5.731886 170.386948 +37.636753 5.731886 170.386932 +40.958637 7.284057 168.834763 +37.636753 7.284058 168.834763 +40.958637 24.287575 168.834763 +37.636757 24.287577 168.834763 +40.958637 25.451704 169.222809 +37.636757 25.451706 169.222809 +40.958637 25.839746 170.386932 +37.636757 25.839748 170.386932 +15.683622 41.531925 173.898239 +15.683622 41.011555 175.479782 +15.683621 39.450439 176.006958 +30.451061 41.531925 173.898239 +30.451061 41.011555 175.479782 +30.451061 39.450439 176.006958 +28.898891 41.531925 168.834763 +30.063019 41.531925 169.222809 +30.063019 38.143372 169.222809 +28.898891 38.143372 168.834763 +17.235792 38.143375 168.834763 +17.235792 41.531925 168.834763 +16.071665 41.531925 169.222809 +16.071665 38.143368 169.222809 +15.683621 38.143368 170.386932 +15.683622 41.531925 170.386948 +30.451061 41.531925 170.386932 +30.451061 38.143372 170.386932 +36.135548 5.731884 129.687149 +30.140888 41.531925 164.689804 +28.970547 41.531925 164.689804 +30.451061 36.318645 129.687149 +40.958641 6.153670 164.689804 +40.958641 0.000000 164.689804 +40.958637 0.000000 169.222778 +40.958633 5.731886 173.898239 +37.636753 5.731886 176.006958 +37.636757 25.839748 176.006958 +15.683621 38.143368 176.006958 +30.451061 38.143372 176.006958 +40.958641 7.312862 164.689804 +40.958641 24.280998 164.689804 +40.958641 25.442301 164.689804 +40.958637 0.000000 170.386948 +40.744812 0.000000 159.364563 +40.958637 37.388954 169.222809 +39.922894 40.496181 169.222809 +36.815666 41.531925 169.222809 +40.958641 37.388954 164.689804 +39.922901 40.496181 164.689804 +36.815670 41.531925 164.689804 +17.307447 41.531925 164.689804 +16.149532 41.531925 164.689804 +30.406414 38.700436 155.009293 +30.406414 37.475731 155.009293 +30.406414 37.475731 155.973785 +30.406414 39.317528 155.973785 +30.406414 37.475731 156.949387 +30.406414 38.700436 156.949387 +17.226278 39.317539 150.531494 +16.363020 39.317539 152.781586 +16.363020 39.317539 146.653397 +17.226278 39.317539 146.822098 +23.048344 39.317539 152.243317 +23.048344 39.317528 155.009293 +19.633884 39.317528 155.009293 +20.210577 39.317539 152.119827 +18.351269 39.317539 145.005432 +18.400295 39.317539 145.881287 +17.518925 39.317539 146.167908 +16.932453 39.317539 145.504303 +16.870573 39.317539 153.938354 +17.640522 39.317539 151.194901 +18.538645 39.317539 151.690582 +17.882185 39.317528 155.009293 +23.048344 39.317539 144.985245 +23.048344 39.317539 145.873962 +17.715460 38.700390 149.870178 +17.715458 38.700390 146.917694 +17.715460 37.475731 146.917694 +17.715460 37.475731 149.870178 +15.873839 38.700390 153.834656 +15.873839 37.475731 153.834656 +15.873839 37.475731 146.557800 +15.873839 38.700390 146.557800 +19.376354 38.700436 156.949387 +23.048344 38.700436 156.949387 +23.048344 37.475731 156.949387 +19.376354 37.475731 156.949387 +23.048344 38.700390 151.616714 +20.345875 38.700390 151.513321 +20.345875 37.475731 151.513321 +23.048344 37.475731 151.616714 +18.323486 38.700390 144.509125 +16.600119 38.700390 145.128250 +16.600119 37.475731 145.128250 +18.323486 37.475731 144.509125 +17.851257 38.700390 146.543961 +18.428076 38.700390 146.377594 +18.428076 37.475731 146.377594 +17.851257 37.475731 146.543961 +15.690271 38.700436 156.949387 +15.690271 37.475731 156.949387 +15.690271 38.700436 155.009293 +15.690271 39.317528 155.973785 +15.690271 37.475731 155.973785 +15.690271 37.475731 155.009293 +16.551750 38.700424 155.009293 +16.551750 37.475731 155.009293 +18.017389 38.700390 150.483063 +18.017389 37.475731 150.483063 +23.048344 38.700390 146.377563 +23.048344 37.475731 146.377563 +23.048344 38.700390 144.481644 +23.048344 37.475731 144.481644 +18.774273 38.700390 151.037842 +18.774273 37.475731 151.037842 +23.048344 39.317528 155.973785 +19.505857 39.317528 155.973785 +28.870407 39.317539 150.531494 +28.870407 39.317539 146.822098 +29.733665 39.317539 146.653397 +29.733665 39.317539 152.781586 +25.886108 39.317539 152.119827 +26.462803 39.317528 155.009293 +27.745419 39.317539 145.005432 +29.164234 39.317539 145.504303 +28.577763 39.317539 146.167908 +27.696392 39.317539 145.881287 +29.226116 39.317539 153.938354 +28.214504 39.317528 155.009293 +27.558041 39.317539 151.690582 +28.456165 39.317539 151.194901 +28.381229 38.700390 149.870178 +28.381229 37.475731 149.870178 +28.381229 37.475731 146.917694 +28.381229 38.700390 146.917694 +30.222847 38.700390 153.834656 +30.222847 38.700390 146.557800 +30.222847 37.475731 146.557800 +30.222847 37.475731 153.834656 +26.720333 38.700436 156.949387 +26.720333 37.475731 156.949387 +25.750813 37.475731 151.513321 +25.750813 38.700390 151.513321 +27.773201 38.700390 144.509125 +27.773201 37.475731 144.509125 +29.496567 37.475731 145.128250 +29.496567 38.700390 145.128250 +28.245430 38.700390 146.543961 +28.245430 37.475731 146.543961 +27.668610 37.475731 146.377594 +27.668610 38.700390 146.377594 +30.406414 38.700436 156.949387 +30.406414 38.700436 155.009293 +30.406414 37.475731 155.973785 +30.406414 39.317528 155.973785 +29.544937 38.700424 155.009293 +29.544937 37.475731 155.009293 +28.079300 38.700390 150.483063 +28.079300 37.475731 150.483063 +27.322414 37.475731 151.037842 +27.322414 38.700390 151.037842 +26.590830 39.317528 155.973785 +-8.461814 -37.475731 156.949387 +-8.461814 -37.475731 155.009293 +30.406414 -37.475731 155.009293 +30.406414 -37.475731 156.949387 +-8.461814 37.475731 155.009293 +-8.461814 37.475731 156.949387 +30.406414 37.475731 155.009293 +30.406414 37.475731 156.949387 +37.636749 0.000000 176.006958 +-15.692151 0.000000 176.006958 +-54.576832 29.057657 130.149490 +-54.703037 30.905771 149.873047 +-54.052593 28.681145 153.535339 +-56.171177 30.846027 149.873047 +-55.428577 31.588629 153.237854 +-53.350780 29.310871 129.687180 +-55.356113 30.047092 147.802063 +-54.093380 5.291624 129.687180 +-54.093380 11.723294 129.687180 +-54.093380 22.302038 129.687180 +-54.576832 5.250237 130.149490 +-54.576832 11.771256 130.149490 +-54.576832 22.254076 130.149490 +-55.356113 3.532016 147.802063 +-55.356106 13.511790 147.802063 +-55.356113 20.513544 147.802063 +-51.859997 4.799234 129.687073 +-53.109226 3.079486 147.357056 +-52.355499 4.752643 130.150406 +-51.860020 21.794851 129.687286 +-51.860020 12.230479 129.687286 +-52.353741 12.268663 130.148636 +-53.109241 13.963755 147.357285 +-53.109241 20.061579 147.357285 +-52.353741 21.756670 130.148636 +-37.354477 28.402401 157.245361 +-54.052601 0.000001 153.535339 +-41.010628 29.423746 153.535339 +-48.926956 29.423746 153.535339 +-52.259315 28.402401 157.245361 +-53.001915 27.659803 157.245361 +-53.001915 0.000001 157.245361 +-48.399532 28.795618 155.817001 +-41.522289 28.795618 155.817001 +-41.010628 26.993145 153.535339 +-48.926956 26.993145 153.535339 +-48.399532 26.993145 155.817001 +-41.522289 26.993145 155.817001 +-53.834232 29.800255 130.149490 +-55.445637 30.163170 149.873047 +-53.310001 29.423746 153.535339 +-55.428577 31.588629 149.873047 +-56.171177 30.846027 153.237854 +-54.093372 28.568272 129.687180 +-54.613514 30.789690 147.802063 +-54.391193 29.614607 130.149490 +-55.259983 30.720119 149.873047 +-53.866955 29.238098 153.535339 +-55.985531 31.402977 149.873047 +-55.985531 31.402977 153.237854 +-53.907726 29.125223 129.687180 +-55.170460 30.604038 147.802063 +-52.816261 28.216753 157.245361 +-51.859997 0.000001 129.687073 +-55.356106 0.000001 147.802063 +-37.354477 31.588629 153.237854 +-37.354477 29.310871 129.687180 +-52.816269 -28.216753 157.245361 +-53.001915 -27.659803 157.245361 +-37.354477 -28.402401 157.245361 +-52.259315 -28.402401 157.245361 +-52.355499 -4.752642 130.150406 +-52.355499 0.000001 130.150406 +-53.109226 0.000001 147.357056 +-53.109226 -3.079484 147.357056 +-56.171185 -30.846027 149.873047 +-56.171177 0.000001 149.873047 +-56.171177 0.000001 153.237854 +-56.171185 -30.846027 153.237854 +-55.445637 -30.163170 149.873047 +-55.445637 0.000001 149.873047 +-53.310001 -29.423746 153.535339 +-48.926956 -29.423746 153.535339 +-41.010632 -29.423746 153.535339 +-37.354477 -31.588629 153.237854 +-55.428585 -31.588629 153.237854 +-54.052601 -28.681145 153.535339 +-53.350780 -29.310871 129.687180 +-53.834240 -29.800255 130.149490 +-37.354477 -29.800255 130.149490 +-37.354477 -29.310871 129.687180 +-54.613514 -30.789690 147.802063 +-54.703037 -30.905771 149.873047 +-55.356113 -20.513544 147.802063 +-55.356113 -30.047092 147.802063 +-54.576839 -29.057657 130.149490 +-54.576839 -22.254076 130.149490 +-53.109241 -13.963753 147.357285 +-53.109241 -20.061579 147.357285 +-52.353748 -21.756670 130.148636 +-52.353741 -12.268661 130.148636 +-55.356113 -3.532014 147.802063 +-55.356106 -13.511788 147.802063 +-54.576832 -11.771255 130.149490 +-54.576832 -5.250235 130.149490 +-54.093380 -28.568272 129.687180 +-54.093380 -22.302038 129.687180 +-51.860020 -21.794851 129.687286 +-51.860020 -12.230477 129.687286 +-54.093380 -11.723292 129.687180 +-54.093380 -5.291622 129.687180 +-51.859997 -4.799233 129.687073 +-37.354477 -31.588629 149.873047 +-55.428585 -31.588629 149.873047 +-41.010632 -26.993145 153.535339 +-48.926956 -26.993145 153.535339 +-48.399532 -26.993145 155.817001 +-41.522293 -26.993145 155.817001 +-48.399532 -28.795618 155.817001 +-41.522293 -28.795618 155.817001 +-55.259983 -30.720119 149.873047 +-55.170467 -30.604038 147.802063 +-55.985531 -31.402977 149.873047 +-55.985531 -31.402977 153.237854 +-53.866955 -29.238098 153.535339 +-53.907726 -29.125223 129.687180 +-54.391193 -29.614607 130.149490 +-21.892693 28.216753 157.245361 +-21.707043 27.659803 157.245361 +-21.707043 -0.000001 157.245361 +-37.354477 0.000000 157.245361 +-22.449642 28.402401 157.245361 +-22.353458 4.752642 130.150406 +-22.353458 -0.000001 130.150406 +-21.599731 -0.000001 147.357056 +-21.599731 3.079484 147.357056 +-18.537777 30.846027 149.873047 +-18.537781 -0.000001 149.873047 +-18.537781 -0.000001 153.237854 +-18.537777 30.846027 153.237854 +-19.263321 30.163170 149.873047 +-19.263321 -0.000001 149.873047 +-21.398952 29.423746 153.535339 +-25.781998 29.423746 153.535339 +-33.698326 29.423746 153.535339 +-37.354477 29.423746 153.535339 +-19.280373 31.588629 153.237854 +-20.656357 28.681145 153.535339 +-20.656357 -0.000001 153.535339 +-21.358177 29.310871 129.687180 +-20.874718 29.800255 130.149490 +-37.354477 29.800255 130.149490 +-20.095440 30.789690 147.802063 +-20.005920 30.905771 149.873047 +-37.354477 30.905771 149.873047 +-37.354477 30.789690 147.802078 +-19.352844 20.513544 147.802063 +-19.352844 30.047092 147.802063 +-20.132122 29.057657 130.149490 +-20.132118 22.254076 130.149490 +-21.599716 13.963753 147.357285 +-21.599716 20.061579 147.357285 +-22.355209 21.756670 130.148636 +-22.355217 12.268661 130.148636 +-19.352844 3.532014 147.802063 +-19.352848 13.511788 147.802063 +-20.132122 11.771255 130.149490 +-20.132122 5.250235 130.149490 +-20.615578 28.568272 129.687180 +-20.615578 22.302038 129.687180 +-22.848938 21.794851 129.687286 +-22.848938 12.230477 129.687286 +-20.615578 11.723292 129.687180 +-20.615578 5.291622 129.687180 +-22.848957 4.799233 129.687073 +-37.354477 31.588629 149.873047 +-19.280373 31.588629 149.873047 +-33.698326 26.993145 153.535339 +-25.781998 26.993145 153.535339 +-26.309425 26.993145 155.817001 +-33.186665 26.993145 155.817001 +-22.848957 -0.000001 129.687073 +-19.352848 -0.000001 147.802063 +-26.309425 28.795618 155.817001 +-33.186665 28.795618 155.817001 +-19.448971 30.720119 149.873047 +-19.538490 30.604038 147.802063 +-18.723427 31.402977 149.873047 +-18.723427 31.402977 153.237854 +-20.842003 29.238098 153.535339 +-20.801228 29.125223 129.687180 +-20.317768 29.614607 130.149490 +-21.892696 -28.216753 157.245361 +-22.449642 -28.402401 157.245361 +-21.707043 -27.659803 157.245361 +-22.353458 -4.752643 130.150406 +-21.599731 -3.079486 147.357056 +-18.537781 -30.846027 149.873047 +-18.537781 -30.846027 153.237854 +-19.263321 -30.163170 149.873047 +-21.398952 -29.423746 153.535339 +-19.280380 -31.588629 153.237854 +-37.354477 -29.423746 153.535339 +-33.698330 -29.423746 153.535339 +-25.782001 -29.423746 153.535339 +-20.656361 -28.681145 153.535339 +-21.358177 -29.310871 129.687180 +-20.874722 -29.800255 130.149490 +-20.095444 -30.789690 147.802063 +-37.354477 -30.789690 147.802078 +-37.354477 -30.905771 149.873047 +-20.005920 -30.905771 149.873047 +-19.352844 -20.513544 147.802063 +-20.132122 -22.254076 130.149490 +-20.132122 -29.057657 130.149490 +-19.352844 -30.047092 147.802063 +-21.599716 -13.963755 147.357285 +-22.355217 -12.268663 130.148636 +-22.355217 -21.756670 130.148636 +-21.599716 -20.061579 147.357285 +-19.352844 -3.532016 147.802063 +-20.132122 -5.250237 130.149490 +-20.132122 -11.771256 130.149490 +-19.352848 -13.511790 147.802063 +-20.615578 -22.302038 129.687180 +-20.615582 -28.568272 129.687180 +-22.848938 -12.230479 129.687286 +-22.848938 -21.794851 129.687286 +-20.615578 -5.291624 129.687180 +-20.615578 -11.723294 129.687180 +-22.848957 -4.799234 129.687073 +-19.280380 -31.588629 149.873047 +-33.698330 -26.993145 153.535339 +-33.186668 -26.993145 155.817001 +-26.309425 -26.993145 155.817001 +-25.782001 -26.993145 153.535339 +-26.309425 -28.795618 155.817001 +-33.186668 -28.795618 155.817001 +-19.538494 -30.604038 147.802063 +-19.448975 -30.720119 149.873047 +-18.723427 -31.402977 153.237854 +-18.723427 -31.402977 149.873047 +-20.842007 -29.238098 153.535339 +-20.317772 -29.614607 130.149490 +-20.801228 -29.125223 129.687180 + - + - - 0 0.9870878 -0.1601809 0 1 0 0 1 0 0 1 0 0 0.986432 -0.1641704 0 0.7071088 -0.7071049 0 0.7013249 -0.7128418 2.58318e-7 -1 0 2.64254e-7 -1 3.06372e-6 2.58318e-7 -1 -6.38884e-7 -0.9870879 0 -0.16018 -1 0 0 -1 2.71718e-7 0 -1 6.7268e-7 0 -0.9861714 0 -0.1657289 0 -0.9996106 -0.02790832 -9.08455e-7 -0.9984422 -0.05579531 1.19549e-6 -0.9984422 -0.05579572 0 -0.6868233 -0.7268245 0 -0.6868219 -0.7268257 0 -0.6868216 -0.7268261 -0.9863993 -0.1625567 -0.02432835 -1 0 5.83388e-7 -0.9997988 0 -0.02006208 -4.22359e-6 -0.1601835 0.9870873 0 0.1601836 0.9870873 -6.07714e-6 -0.1601834 0.9870874 0 0 1 -3.01884e-7 -1 0 0 -1 0 0 -0.9870877 -0.1601811 -7.64499e-7 -1 0 0 -0.9864322 -0.1641693 1 0 0 0.9870873 0 -0.160184 0.986172 0 -0.1657259 -1 0 8.83725e-7 -0.9997988 0 -0.02006196 -0.9997988 0 -0.02006196 0 -1 -6.08475e-7 0 -1 0 0 -1 0 0 -1 -2.62574e-7 6.58836e-7 1 -3.61968e-7 1.37451e-6 1 -3.47637e-6 2.27575e-7 1 1.85833e-6 3.6743e-7 1 1.0503e-6 -0.9873961 0 0.1582689 -0.7098549 0 0.7043481 -0.7098619 0 0.7043409 -0.9870876 -0.1601823 4.33979e-7 -0.7056326 -0.7077815 -0.03358781 -0.7071077 -0.7071059 4.13474e-7 -1 5.07671e-7 0 -1 4.34535e-7 -2.26119e-7 -1 2.29902e-7 0 -0.9870875 1.06397e-6 0.1601827 1 -1.43892e-7 0 1 -8.69075e-7 0 1 -1.41894e-7 0 0.9870873 0 0.1601834 -1.62216e-6 0 1 4.04197e-7 0 1 -1.62216e-6 0 1 -8.43153e-6 0 1 3.85477e-7 0 1 -0.7055894 -0.7053751 -0.06774622 6.23115e-7 0 1 -1 2.53423e-7 -5.8239e-7 -1 1.44541e-7 6.7306e-7 -1 1.61521e-7 1.36213e-7 -1 1.81823e-7 -1.42236e-7 -1 1.28363e-7 -5.82434e-7 -1 2.89053e-7 6.7299e-7 -1 1.85309e-7 1.41806e-7 -1 1.57936e-7 -1.36638e-7 -2.7322e-7 -1 -1.28169e-6 -3.27087e-7 -1 1.01145e-5 -2.68087e-7 -1 -2.81754e-6 -2.72648e-7 -1 2.99858e-6 2.66225e-7 -1 -7.05927e-6 -3.27087e-7 -1 -1.01145e-5 1.81969e-7 -1 -2.33425e-6 2.72648e-7 -1 5.38468e-6 0.278629 -0.944534 0.1738432 0.2048742 -0.9315165 0.3005057 -0.1212346 -0.9439502 -0.3070185 -0.1997055 -0.9568911 -0.2108962 -0.2936673 -0.950362 -0.1028178 0.437375 -0.8984282 0.03911775 -0.6827594 0 0.7306434 -0.1399397 0 0.9901601 -0.6827578 -2.19769e-7 0.7306448 0.4467667 0 -0.8946505 0.1652552 0 -0.9862508 0.1652569 0 -0.9862506 -0.9725064 0 -0.2328764 -0.6614934 0 -0.749951 -0.6614956 0 -0.7499491 -0.03823196 0 -0.999269 -0.1652568 0 -0.9862506 -0.03822946 0 -0.9992691 -0.7592793 -0.6262857 -0.1768087 -0.4373747 -0.8984282 0.03911715 -0.5964136 -0.7752248 0.2081282 0.4667751 -0.877353 -0.1112343 -0.3784908 -0.9224358 0.07653093 0.265752 -0.7562036 -0.59794 0.1997058 -0.956891 -0.2108964 0.4900572 -0.7793552 -0.3904479 0.5964142 -0.7752245 0.2081278 0.2145828 -0.8739152 -0.4361498 -0.08415716 -0.883121 -0.4615353 0 -0.6316557 -0.7752492 0 -0.9029365 -0.4297743 0.01676148 -0.961573 0.2740374 0 -0.4824078 0.8759468 0 -0.9605016 0.2782745 0 -1 2.64534e-6 1.56916e-5 -0.4801356 -0.8771944 0 -0.9999967 -0.002593994 0.7248033 -0.6816616 -0.09998887 0.3784909 -0.9224357 0.07653123 0.7664357 -0.6282345 0.1337828 -0.05820691 -0.9347167 -0.3505949 0 -1 2.0448e-6 0 -0.9285686 -0.371161 0.1212345 -0.9439498 -0.3070198 -0.2048748 -0.9315175 0.3005021 -0.278629 -0.944534 0.1738433 0.2936673 -0.9503622 -0.1028173 0.1399397 0 0.9901601 0.68276 0 0.7306428 0.6827576 -4.39539e-7 0.730645 0 0 -1 0.1744615 0 -0.9846641 0 0 -1 0 0 1 0.1399398 0 0.9901601 0 -0.4824088 0.8759463 0 -0.4824078 0.8759468 -0.9659468 0 0.2587407 -0.9725063 0 -0.2328768 0.6614933 0 -0.7499511 0.9725064 0 -0.2328763 0.6614953 0 -0.7499494 -0.466775 -0.877353 -0.1112335 -0.7248033 -0.6816615 -0.09998899 -0.2145866 -0.8739122 -0.4361538 -0.01676166 -0.9615732 0.2740367 0 -0.9999967 -0.002593874 0 -1 2.25307e-6 -1.64872e-5 -0.4801349 -0.8771947 -0.7055888 -0.7053757 -0.06774663 -0.1598314 -0.9852283 -0.06147646 -0.1074706 -0.7218201 0.6836855 -0.2137202 -0.2137196 0.9532301 -0.5374585 -0.5374583 0.6498285 -0.4566125 -0.4538647 -0.7651875 -0.6756023 -0.1117634 -0.7287458 -0.6764718 -0.1071247 -0.7286359 0.6990305 0 -0.715092 0.1601736 0 -0.9870889 0.1592839 0 -0.9872329 -0.1557462 -0.9754873 0.1554598 0 -1 -3.66334e-6 0 -0.9873964 0.1582666 -0.1601737 0 -0.9870889 -0.7071094 7.34059e-7 0.7071043 -0.9870873 3.54703e-7 0.1601838 -0.7071097 0 0.7071039 -0.3199501 0 0.9474344 0.9870874 0 0.160183 -0.999195 0 -0.04011702 0.7071093 0 0.7071043 -1 0 4.2077e-7 -1 0 4.9274e-7 -1 0 5.43204e-7 0 -0.9996106 -0.02790844 0 -1 0 0 -1 -2.46079e-6 0 -1 2.39763e-7 0 -0.9996106 -0.02790808 -0.9991952 -1.74618e-7 -0.04011255 -0.9991958 4.92441e-7 -0.04009848 -0.999196 -4.30279e-6 -0.040093 0 -1 -2.4496e-6 0 -1 -3.96395e-7 0.9848546 -8.98659e-7 0.1733827 0.9739219 -1.35578e-7 -0.2268836 0.9739232 0 -0.2268784 0.7661257 0 -0.6426908 0.4467697 0 -0.894649 0.984855 -6.34976e-7 0.1733803 -0.3348196 -0.8625778 -0.379283 -0.5132887 -0.6309189 -0.5817869 0.05820697 -0.9347171 -0.3505938 0 -0.4824081 0.8759467 0 -0.4824079 0.8759468 -0.4467697 0 -0.894649 -0.766125 0 -0.6426916 -0.4467667 0 -0.8946505 0.9725065 0 -0.232876 0.9659467 0 0.2587413 -0.1652551 0 -0.9862509 -0.1744604 0 -0.9846642 -0.7077748 -0.7031856 -0.06771242 -0.9859344 -0.1599349 -0.04852175 -0.9867233 -0.1550676 -0.04828184 -0.6987367 -0.6987364 0.1534098 -0.1601814 -0.9870876 2.94412e-7 -0.7218201 -0.1074703 0.6836856 -0.9754872 -0.1557455 0.1554611 1.42234e-6 0.9870871 0.1601845 -0.1102728 -0.6713885 -0.7328557 -0.107384 -0.6719025 -0.7328135 -0.6922404 0 -0.7216671 0 -0.3199425 0.9474371 0 -0.7098583 0.7043446 0 -0.3199415 0.9474374 0 -0.7071087 -0.707105 0 -0.7013257 -0.712841 0 -0.1601837 -0.9870873 0 -0.1595335 -0.9871925 -0.7071004 0 -0.7071132 -0.699027 0 -0.7150954 -0.1592828 0 -0.987233 -0.3147554 -0.03424978 0.9485547 -0.7098534 0 0.7043495 0 -0.7071085 0.7071051 0 -0.9870875 0.1601827 0 -0.9870879 0.1601803 -0.6922457 0 -0.7216619 -0.6922406 0 -0.7216669 -0.6922469 0 -0.7216608 1.44105e-7 0.7071087 0.7071049 1.60712e-6 0.7071068 0.7071068 0.7070983 0 -0.7071154 0.7071012 0 0.7071124 0.1601842 0 0.9870873 -0.1601867 0 0.9870867 -0.999195 -6.06873e-7 -0.04011785 0 -0.9996105 -0.02790832 0 -1 -2.01709e-7 -2.20479e-7 -1 1.35399e-6 -2.58316e-7 -1 -2.30979e-6 -0.9997988 1.18688e-6 -0.02006363 -1 0 5.83845e-7 -1.45202e-6 -0.7071073 0.7071063 0 0.1601839 -0.9870873 0 -0.9873963 0.158268 0 -0.7098578 0.7043452 -0.9997987 0 -0.02006208 -0.999195 -2.22531e-7 -0.04011702 -0.7071072 -0.7071065 5.25018e-7 -0.1601818 -0.9870876 3.09972e-7 -0.1616261 -0.9863744 -0.03070288 -0.9859344 -0.1599349 -0.04852157 -0.9991951 0 -0.04011607 -0.1598315 -0.9852282 -0.0614773 -0.1567754 -0.9857252 -0.06137925 -3.20695e-7 -0.9984423 -0.05579394 0 -0.9984423 -0.05579572 -2.90922e-6 -0.9984422 -0.05579519 -1.70379e-6 -0.9996106 -0.02790665 -3.10814e-6 -0.9984417 -0.05580544 -2.28733e-6 -0.998442 -0.05579948 2.194e-6 -0.9984413 -0.05581086 2.53638e-7 -0.9984423 -0.05579525 0 -0.9984422 -0.05579513 0 -1 -1.55229e-6 -1 1.54676e-7 0 -1 1.71284e-7 -1.33787e-7 -1 2.12911e-7 -1.33787e-7 -0.999195 2.01332e-6 -0.04011696 -1 1.34244e-7 0 -0.2190476 -0.944662 0.2441967 0.08415734 -0.8831214 -0.4615345 0.334819 -0.8625779 -0.3792829 -0.05801951 -0.9170412 0.3945493 -0.9739217 -1.35578e-7 -0.2268846 -0.9848547 -6.50103e-7 0.1733822 -0.9739229 0 -0.2268792 -0.9848549 -5.85297e-7 0.1733808 0.1744579 0 -0.9846646 -0.1157195 -0.7098081 -0.6948248 -0.5178269 -0.6479333 0.5586034 -0.1291518 -0.623757 -0.7708742 -0.2657518 -0.7562035 -0.5979401 -0.1136557 -0.626016 0.7714833 0 -0.9033942 0.4288111 0.11572 -0.70981 -0.6948227 -0.4900569 -0.7793547 -0.3904494 0.05801969 -0.9170417 0.3945482 -0.1399398 0 0.9901601 1.12883e-5 0 -1 0.8661082 0 0.4998565 0.8661106 0 0.4998523 0 -0.7124643 -0.7017084 0.5178266 -0.6479339 0.5586029 0.1291515 -0.6237556 -0.7708753 0.1136562 -0.6260171 0.7714823 0 -0.6322342 0.7747774 0 -0.7098587 0.7043442 -0.03424966 -0.3147612 0.9485529 0 0.1595337 -0.9871926 -0.9870874 -0.1601827 6.11188e-7 0 -0.686823 -0.7268247 -0.9873963 0 0.1582678 -1 0 4.92738e-7 0.1601733 0 0.987089 -1 1.58453e-7 0 -1 2.09567e-7 0 -1 2.70051e-7 0 -1 0 8.84311e-7 5.45731e-7 0.9870876 0.1601817 -0.999195 0 -0.04011702 -1 1.50163e-7 0 0.2190478 -0.944662 0.2441961 -0.7661256 0 -0.642691 0.7661262 0 -0.6426903 -0.8661087 0 0.4998558 -0.9659469 0 0.2587408 0.759279 -0.6262858 -0.1768093 0.03823196 0 -0.9992689 0.03822946 0 -0.9992691 -0.1744571 0 -0.9846648 -1.12883e-5 0 -1 0 0 -1 0 0.9870877 -0.160181 0 1 0 0 1 0 0 1 0 0 0.7071088 -0.7071048 -2.58318e-7 -1 0 -2.58318e-7 -1 0 -2.64254e-7 -1 3.10822e-6 0.9870879 0 -0.1601797 1 2.39111e-7 0 1 5.91958e-7 0 0.9861715 0 -0.1657284 0 -0.9996106 -0.02790832 9.08456e-7 -0.9984422 -0.05579525 0 -0.9996106 -0.02790862 0 -0.6868206 -0.726827 0 -0.6868247 -0.7268232 0 -0.6868193 -0.7268282 0.9863992 -0.1625571 -0.02432841 1 -2.21695e-7 5.83388e-7 0.9870876 -0.1601821 3.74961e-7 0 0.1601837 0.9870873 2.91576e-6 -0.1601836 0.9870873 4.58619e-6 -0.1601831 0.9870874 3.01884e-7 -1 0 0 -0.9870877 -0.1601809 0 -1 0 7.645e-7 -1 0 0 -0.9864322 -0.1641693 -0.9870871 0 -0.1601846 -0.9861717 0 -0.1657267 1 -3.38551e-7 8.83725e-7 0.9997988 0 -0.02006214 1 0 8.84311e-7 0 -1 0 -6.58833e-7 1 -2.44686e-7 -2.27572e-7 1 -5.75571e-7 -1.37449e-6 1 -3.47633e-6 -3.6743e-7 1 0 0.7098549 0 0.7043481 0.9873961 0 0.1582689 0.7098619 0 0.7043409 0.7056325 -0.7077816 -0.03358793 0.7071084 -0.7071052 2.88078e-7 1 8.7345e-7 0 1 2.18195e-7 0 1 0 -4.52238e-7 0.9870875 9.46284e-7 0.1601822 -1 2.61068e-7 0 -1 -1.17929e-6 0 -1 3.4763e-6 0 -0.9870873 -2.38802e-7 0.160184 1.62215e-6 0 1 -4.04197e-7 0 1 8.43149e-6 0 1 -3.85477e-7 0 1 0.7055897 -0.7053749 -0.06774628 0.9859344 -0.1599347 -0.04852157 -6.23115e-7 0 1 1 0 -5.8239e-7 1 3.09113e-7 1.36214e-7 1 2.89083e-7 6.7306e-7 1 0 -1.42236e-7 1 0 -5.82434e-7 1 6.18689e-7 1.41806e-7 1 2.89053e-7 6.7299e-7 1 0 -1.36638e-7 2.7322e-7 -1 2.83455e-6 2.68087e-7 -1 5.33281e-7 3.27087e-7 -1 5.05724e-6 2.72648e-7 -1 -3.59508e-6 -2.66225e-7 -1 -1.25295e-5 -1.93693e-7 -1 6.01096e-6 3.27087e-7 -1 -1.68575e-6 -2.60924e-7 -1 -1.47351e-6 -0.2786288 -0.9445343 0.1738423 0.1212345 -0.9439499 -0.3070192 -0.2048746 -0.9315175 0.3005025 0.1997056 -0.9568908 -0.2108973 -0.4373745 -0.8984284 0.03911739 0.2936668 -0.9503622 -0.1028176 0.1399402 0 0.99016 0.6827595 0 0.7306433 0.682758 -1.75815e-6 0.7306446 -0.1652553 0 -0.9862509 -0.4467671 0 -0.8946504 0.6614949 0 -0.7499498 0.1652568 0 -0.9862506 0.03823196 0 -0.999269 0.7592791 -0.6262861 -0.1768085 0.4373746 -0.8984283 0.03911787 0.4667747 -0.8773532 -0.1112331 -0.4667757 -0.8773525 -0.111234 -0.265752 -0.756204 -0.5979394 -0.199706 -0.9568906 -0.2108983 -0.1212347 -0.9439499 -0.3070192 -0.5964138 -0.7752249 0.2081277 -0.2145825 -0.8739183 -0.4361435 0 -0.6316536 -0.7752509 0.08415788 -0.8831222 -0.4615331 0 -0.9029361 -0.4297748 -0.01676154 -0.9615732 0.2740367 0 -0.4824069 0.8759473 0 -0.4824092 0.8759461 0 -1 2.7761e-6 -1.56916e-5 -0.4801366 -0.8771939 0 -0.9999967 -0.002596437 -0.7248024 -0.6816624 -0.09998863 -0.3784905 -0.9224357 0.07653319 -0.2936671 -0.9503621 -0.1028186 0.05820685 -0.9347169 -0.3505941 0 -1 2.52521e-6 0.2786283 -0.9445343 0.1738424 0.2048748 -0.9315175 0.3005024 -0.6827595 0 0.7306433 -0.1399402 0 0.99016 -0.6827578 0 0.7306448 -0.1744604 0 -0.9846643 0 0 -1 0 -0.4824104 0.8759453 0.9659468 0 0.2587407 -0.9725064 0 -0.2328763 -0.6614942 0 -0.7499504 -0.6614954 0 -0.7499492 0.7248013 -0.6816637 -0.09998881 0.3784903 -0.9224359 0.07653313 0.7664355 -0.6282341 0.1337859 0.5964125 -0.7752259 0.2081276 0.2145859 -0.873916 -0.4361467 0.01676166 -0.9615732 0.2740367 0 -1 2.64534e-6 1.64872e-5 -0.480136 -0.8771941 0.7055885 -0.705376 -0.06774663 0.1598314 -0.9852283 -0.0614764 0.1598315 -0.9852282 -0.0614773 0.1074706 -0.7218199 0.6836857 0.2137191 -0.2137196 0.9532303 0.03424966 -0.3147604 0.9485531 0.4566127 -0.4538648 -0.7651873 0.6756019 -0.1117635 -0.7287462 0.4545233 -0.4559328 -0.7652018 -0.6990299 0 -0.7150925 -0.160174 0 -0.9870889 -0.7070981 0 -0.7071155 0 -1 0 0.1557461 -0.9754874 0.1554599 -0.1592839 0 -0.9872329 0.1601736 0 -0.9870889 0.7071096 6.11522e-7 0.707104 0.9870873 2.8474e-7 0.1601837 0.3199501 0 0.9474344 -0.9870873 0 0.1601838 0.999195 0 -0.0401172 0.999195 0 -0.04011726 -0.707109 0 0.7071046 1 0 4.2077e-7 1 0 4.9274e-7 1 0 5.83845e-7 0 -1 -5.83258e-7 0 -0.9996106 -0.02790856 0 -1 0 0 -0.9996105 -0.02790844 0 -1 0 0 -1 0 -1.19549e-6 -0.9984422 -0.05579507 2.92896e-6 -0.9984423 -0.05579513 0.9991958 2.05138e-7 -0.04009848 0.9991952 -6.00025e-7 -0.04011243 0.9991959 -5.7239e-6 -0.040093 -0.9739217 0 -0.2268847 -0.9848545 0 0.1733831 -0.9739229 0 -0.2268794 -0.4467703 0 -0.8946488 -0.766125 0 -0.6426916 -0.9848549 0 0.173381 0.3348194 -0.8625776 -0.3792834 -0.05820691 -0.9347169 -0.3505941 0.766125 0 -0.6426916 0.4467703 0 -0.8946488 0.4467671 0 -0.8946504 -0.9659468 0 0.2587412 -0.9725065 0 -0.232876 0.1652554 0 -0.9862509 0.1744604 0 -0.9846642 0.7077753 -0.703185 -0.06771254 0.9859343 -0.1599354 -0.04852175 0.1601815 -0.9870876 0 0.6987365 -0.6987366 0.1534094 0.721819 -0.1074717 0.6836866 0.537459 -0.5374579 0.6498283 0.9754872 -0.1557461 0.155461 -1.42234e-6 0.9870874 0.1601831 -5.45732e-7 0.9870874 0.1601834 0.1102726 -0.6713868 -0.7328572 0.6922404 0 -0.7216671 0.6764709 -0.1071243 -0.7286368 0.6922408 0 -0.7216666 0 -0.319941 0.9474376 0 -0.7098588 0.7043441 0 -0.7098582 0.7043446 0 -0.7071088 -0.7071048 0 -0.7013258 -0.7128409 0 -0.1601837 -0.9870873 0.7071006 0 -0.707113 0.6990272 0 -0.7150951 0.3147523 -0.03425014 0.9485557 0.7098534 0 0.7043496 0.3199265 0 0.9474424 -2.2454e-7 -0.9870874 0.1601828 0 -0.7071088 0.7071049 0 -0.9870879 0.1601802 0.6922406 0 -0.7216668 0.6922459 0 -0.7216617 0.6922472 0 -0.7216605 -1.44105e-7 0.7071074 0.7071062 0 0.1601837 0.9870873 -0.1601844 0 0.9870872 -0.707101 0 0.7071126 0.1601868 0 0.9870867 0.1601868 0 0.9870868 1 0 5.43204e-7 0.999195 -8.26818e-7 -0.04011785 5.93155e-7 -0.9984424 -0.05579239 2.20479e-7 -1 -1.98976e-6 0 -1 -2.01709e-7 2.58316e-7 -1 0 0.9997988 1.36444e-6 -0.02006363 0.9997988 0 -0.02006214 1.13216e-6 -0.7071071 0.7071066 0 -0.1595335 -0.9871925 0 0.160184 -0.9870873 0 -0.9873965 0.1582665 0.999195 2.50845e-6 -0.0401169 0.9997988 0 -0.02006214 0.999195 0 -0.0401166 0.1601818 -0.9870876 4.55808e-7 0.7071075 -0.7071061 5.23425e-7 0.161626 -0.9863744 -0.03070265 0.9991951 0 -0.04011607 3.20695e-7 -0.9984425 -0.05579006 0.1567753 -0.9857252 -0.06137931 1.72794e-6 -0.9996106 -0.02790695 3.15784e-6 -0.9984418 -0.05580544 2.32463e-6 -0.9984421 -0.05579906 -2.44768e-7 -0.9984422 -0.05579519 -2.15731e-6 -0.9984415 -0.05581074 0 -0.9984422 -0.05579519 1 4.25821e-7 -1.33787e-7 1 2.37204e-7 0 1 4.25821e-7 -1.33787e-7 1 5.23343e-7 0 0.2190478 -0.9446618 0.2441971 -0.08415722 -0.8831217 -0.461534 0.05801975 -0.9170423 0.3945468 0 -0.9033939 0.4288117 0.9848546 -1.98845e-6 0.1733827 0.9739217 0 -0.2268847 0.9739229 0 -0.2268794 0.9848549 -3.97433e-7 0.1733809 -0.1744576 0 -0.9846647 0 -0.9605011 0.278276 0 -0.9285693 -0.3711591 0.1157194 -0.7098091 -0.6948237 0 -0.7124658 -0.7017068 0.5178264 -0.6479319 0.5586056 0.1136567 -0.6260194 0.7714803 0.1291519 -0.6237561 -0.770875 0.2657517 -0.7562035 -0.5979402 0.4900565 -0.779355 -0.3904491 0 -0.6322322 0.774779 -0.1157198 -0.7098087 -0.6948241 -0.05801969 -0.9170425 0.3945465 0.1399398 0 0.9901601 -1.12883e-5 0 -1 -0.8661082 0 0.4998567 -0.5178261 -0.6479327 0.558605 -0.2190482 -0.9446619 0.2441964 -0.1291515 -0.6237546 -0.7708762 -0.3348184 -0.8625783 -0.3792826 -0.5132874 -0.6309198 -0.5817872 -0.490056 -0.7793556 -0.3904483 -0.1136564 -0.6260207 0.7714793 0 -0.3199424 0.9474371 0 0.7013252 -0.7128415 0.9870876 -0.160182 5.45838e-7 0.1073837 -0.6719009 -0.732815 0 -0.6868243 -0.7268236 0 -0.6868253 -0.7268226 0.9873963 0 0.1582678 1 0 4.92738e-7 -0.1601733 0 0.987089 1 2.68704e-7 0 1 0 0 1 2.70051e-7 0 -1.60712e-6 0.7071076 0.7071061 0.9867236 -0.1550667 -0.0482819 1 0 0 0.7661255 0 -0.642691 -0.7661255 0 -0.642691 0.8661087 0 0.4998558 -0.7592794 -0.6262854 -0.1768091 0.1744571 0 -0.9846648 1.12883e-5 0 -1 0 -0.9870877 -0.160181 0 -1 0 0 -1 0 0 -0.9864322 -0.1641694 0 -0.7071088 -0.7071048 2.64254e-7 1 2.57136e-6 2.58318e-7 1 0 2.58318e-7 1 0 -0.9870879 0 -0.16018 -1 0 0 -1 1.34536e-7 0 0 0.9996106 -0.02790832 -9.08455e-7 0.9984423 -0.05579531 0 0.9996105 -0.02790838 0 0.6868219 -0.7268257 0 0.6868233 -0.7268245 0 0.6868216 -0.7268261 -0.9863993 0.1625567 -0.02432841 -0.9870876 0.1601823 3.74961e-7 0 -0.1601832 0.9870873 -2.91577e-6 0.1601833 0.9870874 -4.58619e-6 0.1601836 0.9870873 -3.01884e-7 1 0 0 0.9870877 -0.160181 0 1 0 -7.64499e-7 1 0 0 0.9864322 -0.1641694 1 -3.47799e-7 0 0.9870873 0 -0.160184 1 -8.6103e-7 0 -1 0 8.83725e-7 -0.9997988 0 -0.02006179 0 1 -6.08475e-7 0 1 0 0 1 -2.62574e-7 6.58835e-7 -1 -3.61967e-7 2.27575e-7 -1 1.85834e-6 1.37451e-6 -1 -3.47637e-6 3.67429e-7 -1 1.0503e-6 -0.9873961 0 0.1582689 -0.7056326 0.7077814 -0.03358793 -0.7071078 0.7071058 2.88077e-7 -1 -1.77366e-7 0 -1 -2.59194e-7 0 -1 -1.08634e-6 -2.26119e-7 -0.9870874 -1.00426e-6 0.1601827 1 1.43892e-7 0 1 1.41894e-7 0 1 8.69075e-7 0 0.9870873 0 0.1601834 -1.62216e-6 0 1 4.04197e-7 0 1 -1.62215e-6 0 1 -8.43149e-6 0 1 3.85477e-7 0 1 -0.7055894 0.7053751 -0.06774622 -0.9859344 0.1599349 -0.04852157 6.23116e-7 0 1 -1 -1.28354e-7 -5.8239e-7 -1 -3.14853e-7 1.36214e-7 -1 -2.89083e-7 6.7306e-7 -1 -1.6335e-7 -1.42236e-7 -1 -2.53443e-7 -5.82434e-7 -1 -3.11797e-7 1.41806e-7 -1 -1.44527e-7 6.7299e-7 -1 -1.80924e-7 -1.36638e-7 -2.7322e-7 1 -1.28169e-6 -2.68087e-7 1 -4.33515e-6 -3.27087e-7 1 1.01145e-5 -2.72648e-7 1 3.5991e-6 2.66225e-7 1 -7.05927e-6 1.81969e-7 1 -1.2011e-6 -3.27087e-7 1 -1.01145e-5 2.72648e-7 1 4.28371e-6 0.278629 0.944534 0.1738432 -0.1212346 0.9439502 -0.3070186 0.2048742 0.9315166 0.3005055 -0.1997056 0.956891 -0.2108963 0.4373749 0.8984282 0.03911769 -0.2936673 0.9503622 -0.1028178 -0.1399397 0 0.9901601 -0.6827579 2.19769e-7 0.7306447 -0.7592791 0.626286 -0.1768086 -0.4373748 0.8984283 0.03911679 -0.466775 0.877353 -0.1112335 0.4667754 0.8773527 -0.1112343 0.2657519 0.7562027 -0.5979411 0.1997058 0.956891 -0.2108964 0.1212344 0.9439495 -0.3070207 0.596414 0.7752247 0.2081277 0.2145828 0.8739153 -0.4361496 0 0.6316556 -0.7752491 -0.08415716 0.8831208 -0.4615358 0 0.9029364 -0.4297742 0.01676148 0.961573 0.2740374 0 0.4824078 0.8759468 0 0.4824081 0.8759467 0 1 2.38382e-6 1.56916e-5 0.4801356 -0.8771943 0 0.9999967 -0.002594053 0.7248035 0.6816614 -0.09998899 0.3784909 0.9224358 0.07653123 0.2936674 0.9503622 -0.1028174 -0.05820691 0.9347166 -0.350595 0 1 2.0448e-6 -0.278629 0.9445341 0.173843 -0.2048748 0.9315176 0.300502 0.6827574 8.79077e-7 0.7306451 0 0 -1 0 0 1 0 0.4824088 0.8759463 0 0.4824078 0.8759468 0.9725064 0 -0.2328763 -0.7248028 0.6816621 -0.09998893 -0.3784908 0.9224358 0.07653099 -0.7664359 0.6282347 0.1337813 -0.5964137 0.7752248 0.2081283 -0.2145866 0.8739122 -0.4361538 -0.01676166 0.9615732 0.2740367 0 0.9999967 -0.002593874 0 1 2.18397e-6 -1.64872e-5 0.4801349 -0.8771947 -0.7055888 0.7053757 -0.06774663 -0.1598315 0.9852283 -0.06147646 -0.1598316 0.9852282 -0.0614773 -0.1074706 0.7218201 0.6836855 -0.2137191 0.2137195 0.9532304 -0.03424966 0.3147613 0.9485527 -0.4566128 0.453864 -0.7651878 -0.6756019 0.1117632 -0.7287462 -0.4545233 0.4559314 -0.7652027 0.6990306 0 -0.7150919 0.1601736 0 -0.9870889 0 1 -3.50263e-6 -0.1557462 0.9754872 0.1554601 0 0.9873964 0.1582666 0.1592839 0 -0.9872329 -0.1601737 0 -0.9870889 -0.7071094 -7.34056e-7 0.7071043 -0.9870873 -3.54703e-7 0.1601838 -0.999195 1.1817e-6 -0.04011684 -0.999195 -1.03848e-6 -0.04011684 -1 0 4.2077e-7 -1 0 5.83845e-7 0 1 0 0 0.9996106 -0.02790844 0 1 -2.46735e-6 0 0.9996106 -0.0279082 0 1 2.39763e-7 0 1 -9.60506e-7 1.19549e-6 0.9984423 -0.05579578 -2.92896e-6 0.9984422 -0.05579525 -0.9991958 -4.85718e-7 -0.04009848 -0.9991952 3.44828e-7 -0.04011243 -0.9991959 4.35812e-6 -0.040093 0 1 -2.47747e-7 0 1 -1.531e-6 0.9739219 1.35578e-7 -0.2268836 0.9848545 1.39577e-6 0.1733831 0.9739232 0 -0.2268784 0.984855 7.34335e-7 0.1733803 -0.3348194 0.8625779 -0.3792828 0.05820697 0.9347171 -0.3505939 0 0.4824079 0.8759468 0.9659467 0 0.2587413 0.9725065 0 -0.232876 -0.1652551 0 -0.9862509 -0.1744604 0 -0.9846643 -0.7077749 0.7031855 -0.06771242 -0.9859344 0.1599349 -0.04852175 -0.1601815 0.9870877 0 -0.6987373 0.6987359 0.1534094 -0.7218191 0.1074708 0.6836865 -0.5374588 0.5374578 0.6498287 -0.9754872 0.1557455 0.1554611 1.42234e-6 -0.9870871 0.1601847 5.45732e-7 -0.9870876 0.1601818 -0.1102728 0.6713883 -0.7328559 -0.6764709 0.1071243 -0.7286368 -0.6922408 0 -0.7216666 0 0.3199425 0.9474371 0 0.7098584 0.7043445 0 0.7098577 0.7043452 0 0.7071087 -0.7071049 0 0.7013254 -0.7128414 0 0.1601837 -0.9870873 -0.699027 0 -0.7150954 -0.3147523 0.0342499 0.9485557 -0.7098534 0 0.7043496 -0.3199265 0 0.9474424 2.24539e-7 0.9870874 0.1601827 0 0.7071084 0.7071052 0 0.9870879 0.1601805 -0.6922406 0 -0.7216668 -0.6922459 0 -0.7216617 -0.6922472 0 -0.7216605 1.44105e-7 -0.7071089 0.7071048 0 -0.1601842 0.9870872 0.7071012 0 0.7071124 -0.1601868 0 0.9870867 -0.1601868 0 0.9870868 -0.999195 6.25927e-7 -0.04011785 -5.93154e-7 0.9984424 -0.05579417 -2.20479e-7 1 1.59105e-6 0 1 -2.01709e-7 -2.58316e-7 1 -3.14524e-6 -0.9997988 -1.18688e-6 -0.02006363 -0.9997987 0 -0.02006202 -1.13216e-6 0.7071075 0.7071062 0 0.1595333 -0.9871926 0 -0.1601837 -0.9870873 0 0.9873963 0.158268 -0.999195 -2.74694e-6 -0.0401169 -0.9997988 0 -0.02006196 -0.9991951 7.54205e-7 -0.0401166 -0.1601819 0.9870876 0 -0.7071072 0.7071065 0 -0.1616261 0.9863744 -0.03070282 -3.20695e-7 0.9984423 -0.055794 -0.1567755 0.9857252 -0.06137925 -1.72794e-6 0.9996106 -0.02790677 -3.15784e-6 0.9984417 -0.05580544 -2.32463e-6 0.998442 -0.05579948 2.44768e-7 0.9984423 -0.05579525 2.15731e-6 0.9984413 -0.05581086 0 0.9984422 -0.05579513 -1 -2.12911e-7 -1.33787e-7 -1 -1.90789e-7 0 -1 -2.12911e-7 -1.33787e-7 -1 -2.65079e-7 0 -0.2190477 0.944662 0.2441968 0.08415734 0.8831216 -0.461534 -0.05801957 0.9170412 0.3945493 0 0.9033942 0.4288111 -0.9848547 6.50103e-7 0.1733821 -0.9739217 1.35578e-7 -0.2268845 -0.9739229 0 -0.2268792 -0.9848549 5.85297e-7 0.1733808 0.1744579 0 -0.9846646 0 0.9605016 0.2782745 0 0.9285686 -0.371161 -0.1157195 0.7098079 -0.694825 0 0.7124643 -0.7017084 -0.5178269 0.6479334 0.5586034 -0.1136556 0.6260161 0.7714833 -0.1291518 0.6237563 -0.7708747 -0.2657519 0.7562035 -0.5979402 -0.4900568 0.7793546 -0.3904494 0 0.6322342 0.7747774 0.11572 0.7098098 -0.694823 0.05801969 0.9170417 0.3945482 -0.1399398 0 0.9901601 0.9659466 0 0.2587417 0.5178269 0.6479336 0.5586031 0.2190478 0.944662 0.2441961 0.1291515 0.6237564 -0.7708748 0.334819 0.862578 -0.3792829 0.5132883 0.6309187 -0.5817876 0.4900574 0.7793549 -0.390448 0.1136562 0.6260171 0.7714823 0 0.7098587 0.7043442 0 0.3199425 0.947437 0 -0.7013257 -0.712841 -0.9870875 0.1601827 5.45838e-7 -0.107384 0.6719025 -0.7328135 0 0.686823 -0.7268248 0 0.6868231 -0.7268246 -0.9873963 0 0.1582678 -1 -2.19589e-7 0 -1 -1.35025e-7 0 1.60712e-6 -0.7071063 0.7071074 -0.9867233 0.1550676 -0.04828184 -1 -1.53571e-7 0 -0.7661256 0 -0.642691 -0.8661106 0 0.4998523 0.7592794 0.6262853 -0.1768093 0 -1 0 0 -1 0 0 -0.986432 -0.1641704 0 -0.7071088 -0.7071048 0 -0.7013252 -0.7128415 -2.58318e-7 1 0 -2.58318e-7 1 0 -2.64254e-7 1 0 0.9870879 0 -0.1601802 1 -2.17374e-7 0 1 -5.38144e-7 0 0.9861715 0 -0.1657288 0 0.9996106 -0.02790832 9.08456e-7 0.9984422 -0.05579549 -1.19549e-6 0.9984422 -0.05579507 0 0.6868247 -0.7268232 0 0.6868206 -0.726827 0 0.6868193 -0.7268282 0.9863992 0.1625571 -0.02432835 1 2.21695e-7 5.83388e-7 0.9997988 0 -0.02006214 4.22359e-6 0.1601836 0.9870873 0 -0.1601837 0.9870873 6.07714e-6 0.1601831 0.9870874 3.01884e-7 1 0 0 1 0 0 0.9870877 -0.1601809 7.645e-7 1 0 0 0.9864322 -0.1641693 -0.9870871 0 -0.1601846 1 3.38551e-7 8.83725e-7 0.9997988 0 -0.0200622 0.9997988 0 -0.02006214 0 1 0 -6.58833e-7 -1 -2.44686e-7 -1.37449e-6 -1 -3.47633e-6 -2.27572e-7 -1 -5.75571e-7 -3.6743e-7 -1 0 0.9873961 0 0.1582689 0.9870876 0.1601821 4.33979e-7 0.7056325 0.7077816 -0.03358781 0.7071084 0.7071052 3.06832e-7 1 -1.01534e-6 0 1 -8.69069e-7 -4.52238e-7 1 -3.62085e-7 0 0.9870875 -1.41099e-6 0.1601827 -1 -2.61068e-7 0 -1 -3.4763e-6 0 -1 1.17929e-6 0 -0.9870873 2.38802e-7 0.160184 1.62215e-6 0 1 -3.85477e-7 0 1 0.7055897 0.7053749 -0.06774628 -6.23115e-7 0 1 1 0 -5.8239e-7 1 -2.89083e-7 6.7306e-7 1 -3.0911e-7 1.36213e-7 1 0 -1.42236e-7 1 0 -5.82434e-7 1 -2.89053e-7 6.7299e-7 1 -6.18689e-7 1.41806e-7 1 0 -1.36638e-7 2.7322e-7 1 2.83455e-6 3.27087e-7 1 5.05724e-6 2.68087e-7 1 1.4304e-6 2.72648e-7 1 4.08379e-7 -2.66225e-7 1 -1.25295e-5 3.27087e-7 1 -1.68575e-6 -1.93693e-7 1 -3.94661e-7 -2.60924e-7 1 -1.74692e-6 -0.2786289 0.9445344 0.1738419 -0.2048746 0.9315176 0.3005021 0.1212341 0.9439495 -0.3070206 0.199705 0.9568908 -0.2108981 0.2936666 0.9503622 -0.1028185 -0.4373738 0.8984287 0.03911745 0.6827567 1.75815e-6 0.7306458 -0.4467669 0 -0.8946505 0.759279 0.6262863 -0.1768074 0.4373728 0.8984292 0.03911745 0.5964117 0.7752264 0.2081274 -0.4667755 0.8773527 -0.1112345 0.3784906 0.9224356 0.07653534 -0.2657517 0.7562034 -0.5979402 -0.199706 0.9568906 -0.2108983 -0.490056 0.7793557 -0.3904483 -0.5964134 0.7752251 0.2081277 -0.2145826 0.8739148 -0.4361504 0.08415722 0.883122 -0.4615336 0 0.6316536 -0.7752508 0 0.9029361 -0.429775 -0.01676154 0.9615729 0.2740378 0 0.4824079 0.8759468 0 0.9605017 0.2782744 0 1 2.52202e-6 -1.56916e-5 0.4801356 -0.8771944 -0.7248024 0.6816624 -0.09998863 -0.3784899 0.9224359 0.07653445 -0.766435 0.6282353 0.1337828 0.05820703 0.9347171 -0.3505939 0 1 2.52521e-6 0 0.9285693 -0.3711591 -0.1212345 0.9439496 -0.30702 0.2048748 0.9315175 0.3005022 0.2786284 0.9445343 0.1738423 -0.293667 0.9503621 -0.1028186 -0.6827589 0 0.7306438 0 0 -1 -0.1744615 0 -0.984664 0 0 1 0 0.4824092 0.875946 0 0.4824106 0.8759452 -0.6614933 0 -0.7499511 -0.9725064 0 -0.2328763 -0.6614952 0 -0.7499494 0.4667748 0.8773533 -0.1112313 0.7248014 0.6816636 -0.09998899 0.2145858 0.873916 -0.4361467 0.0167616 0.9615732 0.2740365 0 0.9999967 -0.002596616 0 1 2.51458e-6 1.64872e-5 0.480136 -0.8771941 0.7055886 0.7053759 -0.06774663 0.1598314 0.9852283 -0.0614764 0.1074706 0.7218199 0.6836857 0.2137202 0.2137196 0.9532302 0.5374588 0.5374581 0.6498284 0.4566127 0.4538648 -0.7651873 0.6756019 0.1117635 -0.7287462 0.6764709 0.1071243 -0.7286369 -0.160174 0 -0.9870889 -0.1592839 0 -0.9872329 0.1557461 0.9754874 0.15546 0 0.9873964 0.1582666 0.1601736 0 -0.9870889 0.7071093 -1.01094e-6 0.7071043 0.9870872 -3.87529e-7 0.160184 0.7071096 0 0.707104 0.999195 0 -0.0401172 1 0 4.2077e-7 0 0.9996105 -0.02790838 0 1 0 0 1 0 0 1 0 0 0.9996106 -0.02790844 0.9991952 5.35851e-7 -0.04011255 0.9991958 -3.07146e-7 -0.04009848 0.999196 5.54665e-6 -0.040093 -0.9848548 0 0.1733813 -0.9739217 0 -0.2268844 -0.9739229 0 -0.2268791 -0.4467697 0 -0.894649 -0.984855 0 0.1733806 0.3348196 0.8625776 -0.3792833 0.513288 0.6309184 -0.5817882 -0.05820685 0.9347169 -0.3505942 0 0.4824074 0.875947 0 0.4824079 0.8759467 0.4467671 0 -0.8946504 -0.9725065 0 -0.232876 0.1652553 0 -0.9862509 0.1744604 0 -0.9846643 0.7077753 0.703185 -0.06771254 0.9859343 0.1599354 -0.04852175 0.9867236 0.1550667 -0.0482819 0.6987362 0.6987369 0.1534097 0.1601815 0.9870877 1.37871e-7 0.7218199 0.1074712 0.6836856 0.9754872 0.1557461 0.155461 -1.42234e-6 -0.9870874 0.1601831 0.1102726 0.6713868 -0.7328572 0.1073837 0.6719009 -0.732815 0 0.3199409 0.9474376 0 0.7098588 0.7043441 0 0.3199428 0.947437 0 0.7071088 -0.7071048 0 0.7013258 -0.7128409 0 0.1601837 -0.9870873 0 0.1595335 -0.9871925 0.7071003 0 -0.7071134 0.6990271 0 -0.7150953 0.1592828 0 -0.987233 0.3147554 0.03425008 0.9485547 0.7098534 0 0.7043495 0 0.7071088 0.7071049 0 0.9870874 0.1601828 0 0.9870879 0.1601803 0.6922457 0 -0.7216619 0.6922406 0 -0.7216669 0.6922469 0 -0.7216608 -1.44105e-7 -0.7071074 0.7071062 -1.60712e-6 -0.7071076 0.707106 0.1601867 0 0.9870867 0.999195 8.09165e-7 -0.04011785 0 0.9996106 -0.02790832 0 1 -2.01709e-7 2.20479e-7 1 0 2.58316e-7 1 3.93155e-7 0.9997988 -1.36444e-6 -0.02006363 1 0 5.83845e-7 1.45202e-6 0.7071071 0.7071066 0 -0.160184 -0.9870873 0 0.9873965 0.1582665 0 0.7098582 0.7043447 0.9997988 0 -0.02006214 0.7071075 0.7071062 6.9705e-7 0.1601818 0.9870876 4.35845e-7 0.161626 0.9863744 -0.03070247 0.9859344 0.1599347 -0.04852157 0.1598315 0.9852282 -0.0614773 0.1567753 0.9857252 -0.06137931 3.20695e-7 0.9984425 -0.05579006 0 0.9984422 -0.05579572 2.90922e-6 0.9984423 -0.05579555 1.70379e-6 0.9996106 -0.02790689 3.10814e-6 0.9984416 -0.05580556 2.28732e-6 0.9984419 -0.05580008 -2.194e-6 0.9984415 -0.05581074 -2.53638e-7 0.9984422 -0.05579519 0 0.9984422 -0.05579519 0 1 -2.1935e-7 1 -2.37204e-7 0 1 -4.25821e-7 -1.33787e-7 1 -4.25821e-7 -1.33787e-7 0.999195 -2.50166e-6 -0.04011702 1 -5.23343e-7 0 0.2190474 0.9446619 0.2441968 -0.08415734 0.8831211 -0.4615351 -0.3348192 0.8625773 -0.3792844 0.05801981 0.9170417 0.3945482 0.9739216 2.71155e-7 -0.2268849 0.9848542 2.79154e-6 0.1733847 0.9739229 0 -0.2268797 0.9848548 1.46867e-6 0.1733814 -0.1744579 0 -0.9846646 0.1157202 0.7098101 -0.6948227 0.5178256 0.6479324 0.5586059 0.1291515 0.623755 -0.7708759 0.2657516 0.7562034 -0.5979403 0.1136567 0.6260176 0.7714818 0 0.9033944 0.4288109 -0.1157197 0.7098088 -0.694824 0.4900563 0.7793551 -0.3904491 -0.05801981 0.9170414 0.3945489 -1.12883e-5 0 -1 -0.8661081 0 0.4998567 -0.8661097 0 0.4998541 0 0.7124657 -0.701707 -0.517827 0.647933 0.5586038 -0.1291515 0.6237549 -0.7708759 -0.1136564 0.6260191 0.7714806 0 0.6322344 0.7747773 0 0.7098587 0.7043442 0.03424966 0.3147604 0.9485531 0 -0.1595338 -0.9871925 0.9870876 0.160182 6.11188e-7 0 0.6868243 -0.7268236 0.9873963 0 0.1582678 1 0 0 1 -2.68703e-7 0 1 -2.70051e-7 0 -5.45732e-7 -0.9870874 0.1601834 0.999195 0 -0.04011702 1 0 0 -0.2190482 0.9446614 0.2441983 0.9659469 0 0.2587408 -0.7592797 0.6262847 -0.1768105 0.1744571 0 -0.9846647 0 -0.6867119 -0.7269297 -0.06729674 -0.6492174 -0.7576199 0 -0.6867119 -0.7269297 -0.9990377 0 -0.04386013 -0.1282728 -0.6111344 -0.781064 -0.3953024 -0.3935441 -0.8299754 -0.9857621 -0.1598954 -0.05202376 -0.999027 0 -0.04410231 -0.9865199 -0.1550779 -0.05224269 -0.217175 -0.9704553 -0.1051266 0 -1 -1.21553e-7 0 -0.9984329 -0.05596268 -0.1563686 -0.9857413 -0.06215405 0 -0.9984329 -0.05596238 -0.1601857 -0.9870869 0 -0.9870879 -0.1601798 0 -0.9757663 0 -0.2188151 -0.9849669 -0.1647899 -0.05181384 -0.7055083 -0.7052023 -0.07034051 -0.7035986 -0.7071366 -0.07004874 -0.7071114 -0.7071023 0 -0.7071093 -0.7071043 0 -2.22209e-5 0 -1 -0.1726688 -0.9360496 0.3065887 -0.6565261 -0.6588346 0.3673016 -0.6585203 -0.6568337 0.3673155 -0.999042 0 -0.04376244 -0.9437708 -0.1312795 0.3034179 -0.9621601 0 0.2724851 -0.9345045 -0.1715559 0.3118814 -0.6532908 -0.067034 -0.7541337 -0.6911213 -8.46006e-7 -0.7227388 -0.6911211 -9.10077e-7 -0.7227391 -0.1306862 -0.945774 0.2973766 -1.6041e-6 -0.9641329 0.2654201 -1.1768e-6 -0.9641326 0.2654213 -0.1137749 -0.02512353 0.9931889 -0.06948345 -0.06875431 0.995211 -0.127994 -0.01102066 0.9917138 -0.6137746 -0.1293887 -0.7788065 0 -0.9984329 -0.05596309 -0.159867 -0.9851767 -0.06220543 -0.999027 0 -0.04410231 -0.691123 0 -0.7227373 -0.2173658 0.9705451 -0.1038967 -0.1941914 0 -0.9809637 -0.2171744 0.9704555 -0.1051262 -0.1390539 0 0.9902849 -0.1390535 0 0.990285 -0.6830195 0 -0.7304002 -0.1942855 0 -0.9809451 1.90284e-6 -0.9641329 0.26542 0.9743076 0 -0.2252216 -0.1632186 -0.9846245 -0.06224513 -0.03432196 -0.1030009 0.994089 -0.0343399 -0.1030031 0.9940882 -0.7070769 -0.7035985 -0.07065141 -0.6827533 0 -0.730649 0 -0.1361347 0.9906904 0 -0.1361348 0.9906904 0 -0.1361348 0.9906904 -0.2110617 0.9293981 -0.3027745 -0.2110544 -0.9293975 -0.3027809 -3.1363e-5 0 -1 -0.9990668 0 -0.04319185 -0.999067 0 -0.0431869 -0.999067 0 -0.04318851 -0.1601828 -0.9870874 0 0 -0.9641332 0.2654191 -0.9990541 0 -0.04348576 -0.204563 0.9277795 -0.3120564 0 -0.6867121 -0.7269296 0.06729638 -0.6492192 -0.7576184 0.1282731 -0.6111354 -0.7810631 0.9990378 0 -0.04386007 0.3953021 -0.3935477 -0.8299739 0.999027 0 -0.04410231 0.9857624 -0.1598939 -0.0520237 0.9865191 -0.1550832 -0.05224263 0.2160901 -0.9706843 -0.1052481 0.1563695 -0.9857411 -0.06215423 0.1598658 -0.9851769 -0.06220543 0.1601848 -0.9870871 0 0.9870879 -0.1601798 0 0.9870879 -0.1601798 0 0.9757666 0 -0.2188138 0.9849674 -0.1647864 -0.05181378 0.7055087 -0.7052019 -0.07034081 0.7071105 -0.7071031 0 0.7071096 -0.707104 0 2.96279e-5 0 -1 0.1726679 -0.9360501 0.3065876 0.6565286 -0.6588314 0.367303 0.130687 -0.9457736 0.2973774 0.999042 0 -0.04376238 0.9437712 -0.1312769 0.3034179 0.9621601 0 0.2724851 0.9621601 0 0.272485 0.6532908 -0.06703686 -0.7541335 0.6911213 -4.23003e-7 -0.7227388 0.6137745 -0.129389 -0.7788065 1.60409e-6 -0.964133 0.2654197 0.06948 -0.0687536 0.9952113 0.1137868 -0.02512389 0.9931875 0.127991 -0.01102048 0.9917141 0.9345049 -0.1715524 0.3118818 0.6585215 -0.6568323 0.3673157 0.3940048 -0.3948421 -0.829976 0.9990271 -3.46121e-7 -0.04410207 0.6911289 0 -0.7227315 0.2173643 0.9705454 -0.1038963 0.194188 0 -0.9809644 0.2171743 0.9704556 -0.1051261 0.1390539 0 0.9902849 0.6829755 0 -0.7304413 0.1942818 2.35761e-7 -0.9809458 0 -0.9641327 0.2654209 -0.9743076 0 -0.2252216 0.163218 -0.9846245 -0.06224566 0.7036007 -0.7071345 -0.07004982 0.03432196 -0.1030019 0.9940889 0.06895738 -0.06926524 0.9952122 0.7070736 -0.7036017 -0.07065123 0.6827404 0 -0.7306611 0 -0.1361348 0.9906904 0 -0.1361347 0.9906904 0 -0.1361346 0.9906904 0.2110545 0.9293987 -0.3027776 0.207488 -0.9267715 -0.3131187 0.9990668 5.25648e-7 -0.04319185 0.999067 -3.68801e-7 -0.0431869 0.999067 1.04203e-6 -0.04318851 0.1601834 -0.9870873 0 0 -0.9641331 0.2654192 0 -0.9641332 0.2654191 0.9990541 0 -0.04348593 0.2045649 0.9277796 -0.3120549 0 0.6867119 -0.7269297 -0.06729674 0.6492174 -0.7576199 -0.1282731 0.6111352 -0.7810633 -0.9990378 0 -0.04386007 -0.3953025 0.3935446 -0.8299751 -0.999027 0 -0.04410231 -0.9857621 0.1598954 -0.0520237 -0.9865199 0.1550779 -0.05224269 -0.2160901 0.9706843 -0.1052481 0 0.9984329 -0.05596268 -0.1563686 0.9857413 -0.06215405 -0.1598668 0.9851767 -0.06220567 -0.1601858 0.987087 0 -0.9870879 0.1601798 0 -0.9870879 0.1601798 0 -0.9757666 0 -0.2188138 -0.9849669 0.1647899 -0.05181372 -0.7055082 0.7052024 -0.07034087 -0.7071114 0.7071023 0 -0.7071093 0.7071043 0 -2.96279e-5 0 -1 -0.1726688 0.9360496 0.3065887 -0.6565262 0.6588346 0.3673014 -0.1306862 0.945774 0.2973766 -0.999042 0 -0.04376238 -0.9437709 0.1312795 0.3034177 -0.9621601 0 0.272485 -0.6532908 0.067034 -0.7541337 -0.6911213 8.46006e-7 -0.7227388 -0.6137746 0.1293887 -0.7788065 -1.6041e-6 0.9641329 0.2654201 -0.06948 0.06875431 0.9952113 -0.1137868 0.02512353 0.9931875 -0.127991 0.01102072 0.9917141 -0.9345044 0.1715559 0.3118817 -0.6585202 0.6568336 0.3673157 -0.3940042 0.3948456 -0.8299745 0 0.9984329 -0.05596309 -0.9990271 0 -0.04410207 -0.6911289 0 -0.7227315 -0.2173654 -0.9705452 -0.1038968 -0.194188 0 -0.9809644 -0.2171747 -0.9704554 -0.1051263 -0.6829755 0 -0.7304413 -0.1942818 0 -0.9809458 0 0.9641327 0.2654209 -0.1632186 0.9846245 -0.06224578 -0.7035986 0.7071366 -0.07004964 -0.03432196 0.1030009 0.994089 -0.06895738 0.06926435 0.9952123 -0.7070769 0.7035985 -0.07065141 -0.6827404 0 -0.7306611 0 0.1361348 0.9906904 0 0.1361348 0.9906904 0 0.1361348 0.9906904 -0.2110546 -0.9293986 -0.3027778 -0.2074874 0.926772 -0.3131177 -0.1601828 0.9870874 0 0 0.9641332 0.2654191 0 0.9641333 0.265419 -0.9990541 0 -0.04348593 -0.2045658 -0.927779 -0.3120562 0 0.6867121 -0.7269296 0.06729638 0.6492192 -0.7576184 0.9990377 0 -0.04386013 0.1282728 0.6111346 -0.7810638 0.3953019 0.3935472 -0.8299741 0.9857624 0.159894 -0.05202382 0.999027 0 -0.04410231 0.9865191 0.1550832 -0.05224263 0.2171747 0.9704554 -0.1051263 0 1 -1.21553e-7 0.1563695 0.9857411 -0.06215423 0 0.9984329 -0.05596238 0.1601848 0.9870871 0 0.9870879 0.1601798 0 0.9757663 0 -0.2188151 0.9849674 0.1647864 -0.05181384 0.7055088 0.7052018 -0.07034045 0.7036008 0.7071346 -0.07004892 0.7071105 0.7071031 0 0.7071096 0.707104 0 2.22209e-5 0 -1 0.1726679 0.9360501 0.3065876 0.6565285 0.6588314 0.3673031 0.6585215 0.6568324 0.3673155 0.999042 0 -0.04376244 0.9437712 0.1312769 0.303418 0.9345051 0.1715524 0.3118817 0.6532906 0.06703686 -0.7541335 0.6911213 4.23003e-7 -0.7227388 0.6911211 4.55038e-7 -0.7227391 0.130687 0.9457736 0.2973774 1.60409e-6 0.964133 0.2654197 1.1768e-6 0.9641327 0.2654211 0.1137749 0.02512389 0.9931889 0.06948345 0.0687536 0.995211 0.127994 0.01102048 0.9917138 0.6137745 0.129389 -0.7788063 0.159866 0.9851769 -0.06220525 0.999027 0 -0.04410231 0.691123 0 -0.7227373 0.2173648 -0.9705453 -0.1038963 0.1941914 0 -0.9809637 0.2171744 -0.9704555 -0.1051262 0.1390539 0 0.9902849 0.1390535 0 0.990285 0.6830195 0 -0.7304002 0.1942855 0 -0.9809451 -1.90284e-6 0.964133 0.2654196 0.163218 0.9846246 -0.06224501 0.03432196 0.1030019 0.9940889 0.0343399 0.1030019 0.9940883 0.7070736 0.7036017 -0.07065123 0.6827533 0 -0.730649 0 0.1361346 0.9906904 0 0.1361348 0.9906904 0 0.1361346 0.9906904 0.2110613 -0.9293982 -0.302774 0.2110543 0.9293977 -0.3027807 3.1363e-5 0 -1 0.9990668 -5.25648e-7 -0.04319185 0.999067 3.68801e-7 -0.0431869 0.999067 -1.04203e-6 -0.04318851 0.1601834 0.9870873 0 0 0.9641331 0.2654192 0.9990541 0 -0.04348576 0.2045624 -0.9277799 -0.3120554 2.58318e-7 -1 0 0 -0.6868237 -0.7268241 0 0.1601836 0.9870873 -0.9873961 0 0.1582689 0 0 1 -0.7664361 -0.6282345 0.1337814 -0.4545228 -0.455932 -0.7652027 -0.3199311 0 0.9474409 -0.6922394 0 -0.721668 -0.999195 0 -0.04011797 -5.93154e-7 -0.9984423 -0.05579417 0 -1 -2.89906e-7 0 -0.9873964 0.1582666 -0.999195 0 -0.0401166 0.5132883 -0.6309186 -0.5817877 0 -0.3199424 0.9474371 0 -0.6868233 -0.7268245 -2.58318e-7 -1 0 0 -0.6868259 -0.726822 0.9873961 0 0.1582689 -0.7664347 -0.6282351 0.1337857 0.7071097 0 0.7071039 0.3199311 0 0.9474409 0.513288 -0.6309184 -0.5817882 0 -0.3199428 0.947437 0.6922394 0 -0.721668 0.999195 0 -0.04011797 0 0.1595338 -0.9871925 0 -0.9873965 0.1582665 0 -0.9984422 -0.05579572 0 0.6868237 -0.7268241 -0.9997988 0 -0.02006173 0.7664358 0.6282345 0.1337829 -0.1592828 0 -0.987233 -0.5132883 0.6309195 -0.5817868 0 0.3199415 0.9474373 0 1 -2.89906e-7 0 -0.1595337 -0.9871925 0 0.9873964 0.1582666 0 0.9984422 -0.05579572 0 0.6868259 -0.726822 0 -0.1601837 0.9870873 0 0 1 0.7664363 0.6282329 0.1337866 0.4545233 0.4559328 -0.7652018 5.93155e-7 0.9984424 -0.05579239 0 1 -2.89906e-7 0 0.9873965 0.1582665 0.999195 0 -0.0401166 -0.5132883 0.6309177 -0.5817886 0 0.3199424 0.9474371 0 0.6868253 -0.7268226 -0.3940038 -0.3948445 -0.8299752 -0.2160901 -0.9706843 -0.1052481 -0.06894797 -0.06926435 0.9952129 4.15061e-5 0 1 -0.2161293 0.9708063 -0.1040351 -0.2160898 0.9706844 -0.1052483 0.9743075 0 -0.2252219 0 -0.1361349 0.9906904 0 -0.1361349 0.9906904 0 -0.1361348 0.9906904 -0.2074794 0.9267735 -0.3131187 -0.2074874 -0.926772 -0.3131177 0 -0.9641333 0.265419 -0.9990671 0 -0.0431872 -0.2083146 0.9305428 -0.3011565 0.2171747 -0.9704554 -0.1051263 -7.40691e-6 0 -1 0.6911211 -4.55038e-7 -0.7227391 1.1768e-6 -0.9641327 0.2654211 -5.53411e-5 0 1 0.2161294 0.9708064 -0.104035 0.2160898 0.9706844 -0.105248 0.1390535 0 0.990285 -1.90284e-6 -0.964133 0.2654196 -0.9743078 0 -0.2252207 0.0343399 -0.1030019 0.9940883 0 -0.1361349 0.9906904 0 -0.1361345 0.9906904 0.2074747 0.9267733 -0.3131228 0.2110543 -0.9293977 -0.3027807 0.999067 0 -0.04318749 0.2083198 0.9305419 -0.3011556 0 0.6867119 -0.7269297 -0.217175 0.9704553 -0.1051266 7.40691e-6 0 -1 -0.6911211 9.10077e-7 -0.7227391 -1.1768e-6 0.9641326 0.2654213 5.53411e-5 0 1 -0.2161294 -0.9708064 -0.104035 -0.2160901 -0.9706843 -0.1052482 1.90284e-6 0.9641329 0.26542 0.9743078 0 -0.2252207 -0.0343399 0.1030031 0.9940882 0 0.1361349 0.9906904 0 0.1361349 0.9906904 -0.2074739 -0.9267736 -0.3131217 -0.2110544 0.9293975 -0.3027809 -0.999067 0 -0.04318749 -0.2083194 -0.9305421 -0.3011552 0.3940044 0.394841 -0.8299766 0.2160901 0.9706843 -0.1052481 0.06894797 0.06926524 0.9952129 -4.15061e-5 0 1 0.9990271 3.46121e-7 -0.04410207 0.216129 -0.9708064 -0.104035 0.194188 0 -0.9809644 0.2160896 -0.9706844 -0.1052482 0.1942818 -2.35761e-7 -0.9809458 -0.9743075 0 -0.2252219 0 0.1361349 0.9906904 0 0.1361345 0.9906904 0.2074797 -0.9267733 -0.3131191 0.207488 0.9267715 -0.3131187 0 0.9641332 0.2654191 0.9990671 0 -0.0431872 0.2083148 -0.9305427 -0.3011568 + + +-0.159831 -0.985228 -0.061474 +-0.705588 -0.705376 -0.067746 +-0.705588 -0.705377 -0.067746 +-0.705588 -0.705377 -0.067746 +-0.159831 -0.985228 -0.061474 +-0.159831 -0.985228 -0.061474 +-0.987087 -0.160182 0.000001 +-0.707107 -0.707107 0.000000 +-0.700073 -0.696893 0.155683 +-0.700073 -0.696893 0.155683 +-0.974743 -0.158179 0.157659 +-0.987087 -0.160182 0.000001 +-0.705588 -0.705377 -0.067746 +-0.705588 -0.705376 -0.067746 +-0.985934 -0.159934 -0.048521 +-0.985934 -0.159934 -0.048521 +-0.985934 -0.159934 -0.048521 +-0.705588 -0.705377 -0.067746 +-0.707107 -0.707107 0.000000 +-0.160182 -0.987087 0.000000 +-0.155746 -0.975487 0.155460 +-0.155746 -0.975487 0.155460 +-0.700073 -0.696893 0.155683 +-0.707107 -0.707107 0.000000 +-0.155928 -0.141040 0.977647 +-0.541660 -0.532699 0.650258 +-0.107470 -0.721820 0.683686 +-0.107470 -0.721820 0.683686 +-0.018551 -0.170483 0.985186 +-0.155928 -0.141040 0.977647 +-0.173478 -0.024209 0.984540 +-0.720099 -0.114166 0.684415 +-0.541660 -0.532699 0.650258 +-0.541660 -0.532699 0.650258 +-0.155928 -0.141040 0.977647 +-0.173478 -0.024209 0.984540 +-0.541660 -0.532699 0.650258 +-0.700073 -0.696893 0.155683 +-0.155746 -0.975487 0.155460 +-0.155746 -0.975487 0.155460 +-0.107470 -0.721820 0.683686 +-0.541660 -0.532699 0.650258 +-0.720099 -0.114166 0.684415 +-0.974743 -0.158179 0.157659 +-0.700073 -0.696893 0.155683 +-0.700073 -0.696893 0.155683 +-0.541660 -0.532699 0.650258 +-0.720099 -0.114166 0.684415 +-0.902713 -0.144766 -0.405157 +-0.676471 -0.107125 -0.728637 +-0.456612 -0.453865 -0.765188 +-0.456612 -0.453865 -0.765188 +-0.645117 -0.643053 -0.412683 +-0.902713 -0.144766 -0.405157 +-0.456612 -0.453865 -0.765188 +-0.107386 -0.671902 -0.732814 +-0.144762 -0.898824 -0.413714 +-0.144762 -0.898824 -0.413714 +-0.645117 -0.643053 -0.412683 +-0.456612 -0.453865 -0.765188 +-0.676471 -0.107125 -0.728637 +-0.902713 -0.144766 -0.405157 +-0.911793 0.000000 -0.410650 +-0.911793 0.000000 -0.410650 +-0.692241 0.000000 -0.721666 +-0.676471 -0.107125 -0.728637 +-0.911793 0.000000 -0.410650 +-0.692242 0.000000 -0.721666 +-0.692241 0.000000 -0.721666 +-0.692241 0.000000 -0.721666 +-0.911793 0.000000 -0.410650 +-0.911793 0.000000 -0.410650 +0.000000 0.987088 -0.160182 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.987088 -0.160182 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.987088 -0.160182 +0.000000 1.000000 0.000000 +0.000000 0.986432 -0.164170 +0.000000 0.986432 -0.164170 +0.000000 0.701326 -0.712841 +0.000000 0.707108 -0.707105 +0.000000 0.707108 -0.707105 +0.000000 0.987088 -0.160182 +0.000000 0.986432 -0.164170 +0.000000 0.701326 -0.712841 +0.000000 0.159534 -0.987192 +0.000000 0.160184 -0.987087 +0.000000 0.160184 -0.987087 +0.000000 0.707108 -0.707105 +0.000000 0.701326 -0.712841 +0.000000 0.159534 -0.987192 +-0.000000 -0.159534 -0.987193 +-0.000000 -0.160184 -0.987087 +-0.000000 -0.160184 -0.987087 +0.000000 0.160184 -0.987087 +0.000000 0.159534 -0.987192 +-0.000000 -0.160184 -0.987087 +-0.000000 -0.159534 -0.987193 +-0.000000 -0.701324 -0.712842 +-0.000000 -0.701324 -0.712842 +-0.000000 -0.707107 -0.707106 +-0.000000 -0.160184 -0.987087 +-0.000000 -0.707107 -0.707106 +-0.000000 -0.701324 -0.712842 +-0.000000 -0.986432 -0.164171 +-0.000000 -0.986432 -0.164171 +-0.000000 -0.987087 -0.160183 +-0.000000 -0.707107 -0.707106 +0.000000 -0.686823 -0.726825 +0.000000 -0.686823 -0.726825 +0.000000 -0.906973 -0.421189 +0.000000 -0.906973 -0.421189 +0.000000 -0.906973 -0.421189 +0.000000 -0.686823 -0.726825 +0.000000 -0.906973 -0.421189 +-0.144762 -0.898824 -0.413714 +-0.107386 -0.671902 -0.732814 +-0.107386 -0.671902 -0.732814 +0.000000 -0.686823 -0.726825 +0.000000 -0.906973 -0.421189 +0.160183 0.000000 -0.987087 +0.159277 0.000000 -0.987234 +0.699024 0.000000 -0.715099 +0.699024 0.000000 -0.715099 +0.707108 0.000000 -0.707105 +0.160183 0.000000 -0.987087 +0.707108 0.000000 -0.707105 +0.699024 0.000000 -0.715099 +0.986171 0.000000 -0.165731 +0.986171 0.000000 -0.165731 +0.987087 0.000000 -0.160182 +0.707108 0.000000 -0.707105 +-0.987088 0.000000 -0.160181 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987088 0.000000 -0.160181 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987088 0.000000 -0.160181 +-1.000000 0.000000 0.000000 +-0.986171 0.000000 -0.165730 +-0.986171 0.000000 -0.165730 +-0.699024 0.000000 -0.715098 +-0.707109 0.000000 -0.707105 +-0.707109 0.000000 -0.707105 +-0.987088 0.000000 -0.160181 +-0.986171 0.000000 -0.165730 +-0.699024 0.000000 -0.715098 +-0.159277 0.000000 -0.987234 +-0.160184 0.000000 -0.987087 +-0.160184 0.000000 -0.987087 +-0.707109 0.000000 -0.707105 +-0.699024 0.000000 -0.715098 +-0.159277 0.000000 -0.987234 +0.159277 0.000000 -0.987234 +0.160183 0.000000 -0.987087 +0.160183 0.000000 -0.987087 +-0.160184 0.000000 -0.987087 +-0.159277 0.000000 -0.987234 +-0.987396 0.000000 0.158268 +-0.974743 -0.158179 0.157659 +-0.720099 -0.114166 0.684415 +-0.720099 -0.114166 0.684415 +-0.709858 0.000000 0.704345 +-0.987396 0.000000 0.158268 +-0.709858 0.000000 0.704345 +-0.720099 -0.114166 0.684415 +-0.173478 -0.024209 0.984540 +-0.173478 -0.024209 0.984540 +-0.162115 0.000000 0.986772 +-0.709858 0.000000 0.704345 +-0.162115 0.000000 0.986772 +-0.162115 0.000000 0.986772 +-0.709857 0.000000 0.704345 +-0.709857 0.000000 0.704345 +-0.709857 0.000000 0.704345 +-0.162115 0.000000 0.986772 +0.000000 -0.707107 0.707106 +0.000001 -0.987087 0.160183 +-0.000000 -0.987088 0.160181 +-0.000000 -0.987088 0.160181 +-0.000000 -0.707109 0.707105 +0.000000 -0.707107 0.707106 +-0.000000 -0.160184 0.987087 +-0.000000 -0.160183 0.987087 +0.000000 -0.707107 0.707106 +0.000000 -0.707107 0.707106 +-0.000000 -0.707109 0.707105 +-0.000000 -0.160184 0.987087 +0.000000 0.160183 0.987087 +0.000000 0.160183 0.987087 +-0.000000 -0.160183 0.987087 +-0.000000 -0.160183 0.987087 +-0.000000 -0.160184 0.987087 +0.000000 0.160183 0.987087 +0.000000 0.707107 0.707106 +0.000000 0.707107 0.707106 +0.000000 0.160183 0.987087 +0.000000 0.160183 0.987087 +0.000000 0.160183 0.987087 +0.000000 0.707107 0.707106 +0.000001 0.987087 0.160183 +0.000001 0.987087 0.160183 +0.000000 0.707107 0.707106 +0.000000 0.707107 0.707106 +0.000000 0.707107 0.707106 +0.000001 0.987087 0.160183 +0.000000 -0.987396 0.158267 +0.000000 -0.709859 0.704344 +0.000000 -0.709859 0.704344 +0.000000 -0.709859 0.704344 +0.000000 -0.987396 0.158267 +0.000000 -0.987396 0.158267 +0.000000 -0.709859 0.704344 +0.000000 -0.162115 0.986772 +0.000000 -0.162115 0.986772 +0.000000 -0.162115 0.986772 +0.000000 -0.709859 0.704344 +0.000000 -0.709859 0.704344 +0.000000 -0.987396 0.158267 +0.000000 -0.709858 0.704344 +-0.107470 -0.721820 0.683686 +-0.107470 -0.721820 0.683686 +-0.155746 -0.975487 0.155460 +0.000000 -0.987396 0.158267 +-0.018551 -0.170483 0.985186 +-0.107470 -0.721820 0.683686 +0.000000 -0.709858 0.704344 +0.000000 -0.709858 0.704344 +0.000000 -0.162115 0.986772 +-0.018551 -0.170483 0.985186 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.707108 0.000001 0.707105 +-0.707108 0.000000 0.707106 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.707108 0.000001 0.707105 +-0.987087 0.000000 0.160183 +-0.707108 0.000000 0.707106 +-0.707108 0.000001 0.707105 +-0.707108 0.000001 0.707105 +-0.987088 0.000001 0.160181 +-0.987087 0.000000 0.160183 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.987087 0.000000 0.160183 +0.987087 0.000000 0.160183 +0.987087 0.000000 0.160183 +0.707107 0.000000 0.707107 +-0.911793 0.000000 -0.410650 +-0.911793 0.000000 -0.410650 +-0.999195 -0.000005 -0.040118 +-0.999195 -0.000005 -0.040118 +-0.999196 0.000000 -0.040096 +-0.911793 0.000000 -0.410650 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.987087 -0.160183 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.987087 -0.160183 +-0.000000 -1.000000 0.000000 +-0.000000 -0.987087 -0.160183 +-0.000000 -0.986432 -0.164171 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.000001 -0.998442 -0.055795 +0.000000 -0.999610 -0.027908 +-0.000000 -0.999610 -0.027908 +-0.000000 -0.999610 -0.027908 +-0.000000 -0.998442 -0.055795 +-0.000001 -0.998442 -0.055795 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.987087 0.000000 -0.160182 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.987087 0.000000 -0.160182 +1.000000 0.000000 0.000000 +0.987087 0.000000 -0.160182 +0.986171 0.000000 -0.165731 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-1.000000 -0.000000 0.000001 +-1.000000 0.000000 0.000000 +-0.999799 0.000000 -0.020064 +-0.999799 0.000000 -0.020064 +-0.999799 -0.000000 -0.020062 +-1.000000 -0.000000 0.000001 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +0.000001 -0.987087 0.160183 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +0.000001 -0.987087 0.160183 +-0.000000 -1.000000 0.000000 +-0.000000 -0.987088 0.160181 +0.000001 1.000000 -0.000000 +0.000001 1.000000 -0.000000 +0.000000 1.000000 0.000001 +0.000001 1.000000 -0.000000 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000000 +0.000001 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000001 0.987087 0.160183 +0.000001 1.000000 -0.000000 +0.000001 0.987087 0.160183 +0.000001 0.987087 0.160183 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-0.162115 0.000000 0.986772 +-0.162115 0.000000 0.986772 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.162115 0.000000 0.986772 +-0.160182 -0.987087 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.987396 0.158267 +0.000000 -0.987396 0.158267 +-0.155746 -0.975487 0.155460 +-0.160182 -0.987087 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.987088 0.000001 0.160181 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.987087 0.000000 0.160183 +-0.987088 0.000001 0.160181 +-1.000000 0.000000 -0.000000 +-0.987087 0.000000 0.160183 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.987087 0.000000 0.160183 +1.000000 0.000000 0.000000 +0.987087 0.000000 0.160183 +0.987087 0.000000 0.160183 +1.000000 0.000000 0.000000 +0.987087 0.000000 0.160183 +1.000000 0.000000 0.000000 +-0.987396 0.000000 0.158268 +-0.709857 0.000000 0.704345 +-0.709857 0.000000 0.704345 +-0.709857 0.000000 0.704345 +-0.987396 0.000000 0.158268 +-0.987396 0.000000 0.158268 +0.000000 0.000000 1.000000 +-0.162115 0.000000 0.986772 +-0.173478 -0.024209 0.984540 +-0.018551 -0.170483 0.985186 +0.000000 -0.162115 0.986772 +0.000000 0.000000 1.000000 +-0.173478 -0.024209 0.984540 +-0.018551 -0.170483 0.985186 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.173478 -0.024209 0.984540 +0.000000 0.000000 1.000000 +-0.173478 -0.024209 0.984540 +-0.155928 -0.141040 0.977647 +-0.018551 -0.170483 0.985186 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.162115 0.986772 +0.000000 -0.162115 0.986772 +0.000000 -0.162115 0.986772 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999195 0.000000 -0.040117 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999195 -0.000000 -0.040117 +-0.999195 0.000000 -0.040117 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 -0.000000 0.000001 +-0.999799 0.000000 -0.020062 +-0.999195 0.000000 -0.040116 +-0.985934 -0.159934 -0.048521 +-0.985934 -0.159934 -0.048521 +-0.985934 -0.159934 -0.048521 +-0.999195 0.000000 -0.040117 +-0.999195 0.000000 -0.040116 +-0.974743 -0.158179 0.157659 +-0.987396 0.000000 0.158268 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987087 -0.160182 0.000001 +-0.974743 -0.158179 0.157659 +-1.000000 0.000000 0.000001 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999195 0.000000 -0.040117 +-0.999195 0.000000 -0.040117 +-0.999195 0.000000 -0.040117 +-0.999799 0.000000 -0.020062 +-0.999195 -0.000000 -0.040117 +-0.999799 0.000000 -0.020062 +-0.999799 -0.000000 -0.020062 +-0.999799 -0.000000 -0.020062 +-0.999195 -0.000000 -0.040116 +-0.999195 -0.000000 -0.040117 +-0.999799 -0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-1.000000 -0.000000 0.000001 +-1.000000 -0.000000 0.000001 +-1.000000 -0.000000 0.000001 +-0.999799 -0.000000 -0.020062 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000001 +-1.000000 0.000000 0.000000 +-0.999195 -0.000000 -0.040116 +-0.999196 0.000000 -0.040095 +-0.999196 0.000000 -0.040096 +-0.999196 0.000000 -0.040096 +-0.999195 -0.000005 -0.040118 +-0.999195 -0.000000 -0.040116 +-1.000000 0.000000 0.000001 +-0.987087 -0.160182 0.000000 +-0.987087 -0.160182 0.000001 +-0.987087 -0.160182 0.000001 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000001 +-0.987087 -0.160182 0.000000 +-0.707106 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.987087 -0.160182 0.000001 +-0.987087 -0.160182 0.000000 +-0.707106 -0.707107 0.000000 +-0.160182 -0.987087 0.000000 +-0.160182 -0.987087 0.000000 +-0.160182 -0.987087 0.000000 +-0.707107 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.160182 -0.987087 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.160182 -0.987087 0.000000 +-0.160182 -0.987087 0.000000 +-1.000000 0.000000 0.000001 +-0.999799 0.000000 -0.020062 +-0.986399 -0.162556 -0.024328 +-0.986399 -0.162556 -0.024328 +-0.987087 -0.160182 0.000000 +-1.000000 0.000000 0.000001 +-0.986399 -0.162556 -0.024328 +-0.705633 -0.707781 -0.033588 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.987087 -0.160182 0.000000 +-0.986399 -0.162556 -0.024328 +-0.705633 -0.707781 -0.033588 +-0.161626 -0.986374 -0.030703 +-0.160182 -0.987087 0.000000 +-0.160182 -0.987087 0.000000 +-0.707106 -0.707107 0.000000 +-0.705633 -0.707781 -0.033588 +0.000000 -0.999610 -0.027908 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000000 -0.999610 -0.027908 +0.000000 -0.999610 -0.027908 +-0.000001 -0.998442 -0.055795 +0.000001 -0.998442 -0.055795 +0.000000 -0.999610 -0.027908 +0.000000 -0.999610 -0.027908 +0.000000 -0.999610 -0.027908 +-0.000001 -0.998442 -0.055795 +0.000000 -0.999610 -0.027908 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.999610 -0.027908 +0.000000 -0.999610 -0.027908 +-0.161626 -0.986374 -0.030703 +-0.000000 -0.999610 -0.027908 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.160182 -0.987087 0.000000 +-0.161626 -0.986374 -0.030703 +-0.159831 -0.985228 -0.061474 +-0.159831 -0.985228 -0.061474 +-0.000000 -0.998442 -0.055794 +-0.000000 -0.998442 -0.055794 +-0.000000 -0.998442 -0.055795 +-0.159831 -0.985228 -0.061474 +-0.000000 -0.999610 -0.027908 +-0.161626 -0.986374 -0.030703 +-0.159831 -0.985228 -0.061474 +-0.159831 -0.985228 -0.061474 +-0.000000 -0.998442 -0.055795 +-0.000000 -0.999610 -0.027908 +-0.161626 -0.986374 -0.030703 +-0.705633 -0.707781 -0.033588 +-0.705588 -0.705376 -0.067746 +-0.705588 -0.705376 -0.067746 +-0.159831 -0.985228 -0.061474 +-0.161626 -0.986374 -0.030703 +-0.705588 -0.705376 -0.067746 +-0.705633 -0.707781 -0.033588 +-0.986399 -0.162556 -0.024328 +-0.986399 -0.162556 -0.024328 +-0.985934 -0.159934 -0.048521 +-0.705588 -0.705376 -0.067746 +-0.999195 0.000000 -0.040117 +-0.985934 -0.159934 -0.048521 +-0.986399 -0.162556 -0.024328 +-0.986399 -0.162556 -0.024328 +-0.999799 0.000000 -0.020062 +-0.999195 0.000000 -0.040117 +-0.999195 0.000000 -0.040116 +-0.911793 0.000000 -0.410650 +-0.902713 -0.144766 -0.405157 +-0.902713 -0.144766 -0.405157 +-0.985934 -0.159934 -0.048521 +-0.999195 0.000000 -0.040116 +-0.985934 -0.159934 -0.048521 +-0.902713 -0.144766 -0.405157 +-0.645117 -0.643053 -0.412683 +-0.645117 -0.643053 -0.412683 +-0.705588 -0.705377 -0.067746 +-0.985934 -0.159934 -0.048521 +-0.645117 -0.643053 -0.412683 +-0.144762 -0.898824 -0.413714 +-0.159831 -0.985228 -0.061474 +-0.159831 -0.985228 -0.061474 +-0.705588 -0.705377 -0.067746 +-0.645117 -0.643053 -0.412683 +-0.144762 -0.898824 -0.413714 +0.000000 -0.906973 -0.421189 +-0.000000 -0.998442 -0.055794 +-0.000000 -0.998442 -0.055794 +-0.159831 -0.985228 -0.061474 +-0.144762 -0.898824 -0.413714 +-0.000000 -0.998441 -0.055810 +0.000000 -0.999611 -0.027905 +-0.000001 -0.999610 -0.027908 +-0.000001 -0.999610 -0.027908 +-0.000005 -0.998442 -0.055795 +-0.000000 -0.998441 -0.055810 +0.000000 -0.987396 0.158267 +0.000000 -0.987396 0.158267 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.987396 0.158267 +0.000000 -1.000000 0.000000 +0.000000 -0.999610 -0.027908 +-0.000001 -0.999610 -0.027908 +-0.000001 -0.999610 -0.027908 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000001 -0.999610 -0.027908 +0.000000 -0.999610 -0.027908 +0.000001 -0.998442 -0.055795 +0.000001 -0.998442 -0.055795 +-0.000005 -0.998442 -0.055795 +-0.000001 -0.999610 -0.027908 +-0.000002 -0.998442 -0.055798 +-0.000000 -0.998441 -0.055815 +-0.000000 -0.998441 -0.055810 +-0.000000 -0.998441 -0.055810 +-0.000005 -0.998442 -0.055795 +-0.000002 -0.998442 -0.055798 +-0.000002 -0.998442 -0.055798 +0.000000 -0.906973 -0.421189 +0.000000 -0.906973 -0.421189 +0.000000 -0.906973 -0.421189 +-0.000000 -0.998441 -0.055815 +-0.000002 -0.998442 -0.055798 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000001 -0.999610 -0.027908 +0.000000 -0.999611 -0.027905 +0.000000 -0.999611 -0.027905 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.987396 0.000000 0.158268 +-0.987396 0.000000 0.158268 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000000 +-0.987396 0.000000 0.158268 +-0.999195 -0.000000 -0.040116 +-0.999799 -0.000000 -0.020062 +-0.999799 0.000000 -0.020064 +-0.999799 0.000000 -0.020064 +-0.999196 0.000000 -0.040095 +-0.999195 -0.000000 -0.040116 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000001 +-1.000000 0.000000 -0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000001 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000001 +-0.000000 -1.000000 0.000001 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000001 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000003 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000001 +-0.000000 -1.000000 0.000021 +0.000000 -1.000000 0.000003 +0.000000 -1.000000 0.000003 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000001 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.293668 -0.950362 -0.102818 +-0.378489 -0.922436 0.076533 +0.466777 -0.877351 -0.111237 +0.466777 -0.877351 -0.111237 +0.437377 -0.898427 0.039117 +-0.293668 -0.950362 -0.102818 +-0.000000 -1.000000 0.000002 +0.000000 -0.928568 -0.371161 +-0.053947 -0.933079 -0.355602 +-0.053947 -0.933079 -0.355602 +0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000002 +0.083860 -0.883048 -0.461729 +0.334821 -0.862576 -0.379284 +-0.219047 -0.944662 0.244197 +-0.219047 -0.944662 0.244197 +-0.058021 -0.917041 0.394549 +0.083860 -0.883048 -0.461729 +0.278630 -0.944534 0.173843 +0.204871 -0.931518 0.300504 +-0.126855 -0.942566 -0.308993 +-0.126855 -0.942566 -0.308993 +-0.199706 -0.956891 -0.210898 +0.278630 -0.944534 0.173843 +0.437377 -0.898427 0.039117 +0.278630 -0.944534 0.173843 +-0.199706 -0.956891 -0.210898 +-0.199706 -0.956891 -0.210898 +-0.293668 -0.950362 -0.102818 +0.437377 -0.898427 0.039117 +0.000000 -0.902777 -0.430109 +0.083860 -0.883048 -0.461729 +-0.058021 -0.917041 0.394549 +-0.058021 -0.917041 0.394549 +0.000000 -0.903393 0.428813 +0.000000 -0.902777 -0.430109 +-0.219047 -0.944662 0.244197 +0.334821 -0.862576 -0.379284 +0.466777 -0.877351 -0.111237 +0.466777 -0.877351 -0.111237 +-0.378489 -0.922436 0.076533 +-0.219047 -0.944662 0.244197 +0.204871 -0.931518 0.300504 +0.000000 -1.000000 0.000002 +-0.053947 -0.933079 -0.355602 +-0.053947 -0.933079 -0.355602 +-0.126855 -0.942566 -0.308993 +0.204871 -0.931518 0.300504 +-0.984855 -0.000001 0.173381 +-0.924386 -0.345298 0.162109 +-0.906193 -0.386266 -0.172083 +-0.906193 -0.386266 -0.172083 +-0.973923 0.000000 -0.226877 +-0.984855 -0.000001 0.173381 +0.965948 0.000000 0.258737 +0.876796 -0.404449 0.260095 +0.922754 -0.317517 -0.218422 +0.922754 -0.317517 -0.218422 +0.972507 0.000000 -0.232875 +0.965948 0.000000 0.258737 +0.000000 0.000000 1.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.165253 0.000000 -0.986251 +-0.145080 -0.399992 -0.904963 +0.000000 -0.389580 -0.920992 +0.000000 -0.389580 -0.920992 +0.000000 0.000000 -1.000000 +-0.165253 0.000000 -0.986251 +0.661497 0.000000 -0.749948 +0.628452 -0.312262 -0.712418 +0.161326 -0.320071 -0.933557 +0.161326 -0.320071 -0.933557 +0.174458 0.000000 -0.984665 +0.661497 0.000000 -0.749948 +-0.139943 0.000000 0.990160 +-0.134000 -0.341445 0.930301 +-0.629331 -0.383170 0.676108 +-0.629331 -0.383170 0.676108 +-0.682762 -0.000000 0.730641 +-0.139943 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000001 -0.480135 -0.877194 +0.472043 -0.840449 -0.266122 +0.472043 -0.840449 -0.266122 +0.865983 0.000000 -0.500074 +0.000000 0.000000 -1.000000 +-0.973923 0.000000 -0.226877 +-0.906193 -0.386266 -0.172083 +-0.686198 -0.460064 -0.563448 +-0.686198 -0.460064 -0.563448 +-0.766123 0.000000 -0.642694 +-0.973923 0.000000 -0.226877 +0.865983 0.000000 -0.500074 +0.472043 -0.840449 -0.266122 +0.876796 -0.404449 0.260095 +0.876796 -0.404449 0.260095 +0.965948 0.000000 0.258737 +0.865983 0.000000 -0.500074 +0.000000 0.000000 1.000000 +0.000000 -0.335574 0.942014 +-0.134000 -0.341445 0.930301 +-0.134000 -0.341445 0.930301 +-0.139943 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.174458 0.000000 -0.984665 +0.161326 -0.320071 -0.933557 +-0.000000 -0.335181 -0.942154 +-0.000000 -0.335181 -0.942154 +0.000000 0.000000 -1.000000 +0.174458 0.000000 -0.984665 +0.972507 0.000000 -0.232875 +0.922754 -0.317517 -0.218422 +0.628452 -0.312262 -0.712418 +0.628452 -0.312262 -0.712418 +0.661497 0.000000 -0.749948 +0.972507 0.000000 -0.232875 +-0.682762 -0.000000 0.730641 +-0.629331 -0.383170 0.676108 +-0.924386 -0.345298 0.162109 +-0.924386 -0.345298 0.162109 +-0.984855 -0.000001 0.173381 +-0.682762 -0.000000 0.730641 +-0.446771 0.000000 -0.894648 +-0.391985 -0.437360 -0.809360 +-0.145080 -0.399992 -0.904963 +-0.145080 -0.399992 -0.904963 +-0.165253 0.000000 -0.986251 +-0.446771 0.000000 -0.894648 +-0.766123 0.000000 -0.642694 +-0.686198 -0.460064 -0.563448 +-0.391985 -0.437360 -0.809360 +-0.391985 -0.437360 -0.809360 +-0.446771 0.000000 -0.894648 +-0.766123 0.000000 -0.642694 +0.437377 -0.898427 0.039117 +0.466777 -0.877351 -0.111237 +0.922754 -0.317517 -0.218422 +0.922754 -0.317517 -0.218422 +0.876796 -0.404449 0.260095 +0.437377 -0.898427 0.039117 +-0.378489 -0.922436 0.076533 +-0.293668 -0.950362 -0.102818 +-0.906193 -0.386266 -0.172083 +-0.906193 -0.386266 -0.172083 +-0.924386 -0.345298 0.162109 +-0.378489 -0.922436 0.076533 +0.000000 -0.960502 0.278273 +-0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.016761 -0.961573 0.274037 +0.000000 -0.960502 0.278273 +-0.145080 -0.399992 -0.904963 +-0.053947 -0.933079 -0.355602 +0.000000 -0.928568 -0.371161 +0.000000 -0.928568 -0.371161 +0.000000 -0.389580 -0.920992 +-0.145080 -0.399992 -0.904963 +-0.058021 -0.917041 0.394549 +-0.219047 -0.944662 0.244197 +-0.629331 -0.383170 0.676108 +-0.629331 -0.383170 0.676108 +-0.134000 -0.341445 0.930301 +-0.058021 -0.917041 0.394549 +0.334821 -0.862576 -0.379284 +0.083860 -0.883048 -0.461729 +0.161326 -0.320071 -0.933557 +0.161326 -0.320071 -0.933557 +0.628452 -0.312262 -0.712418 +0.334821 -0.862576 -0.379284 +-0.199706 -0.956891 -0.210898 +-0.126855 -0.942566 -0.308993 +-0.391985 -0.437360 -0.809360 +-0.391985 -0.437360 -0.809360 +-0.686198 -0.460064 -0.563448 +-0.199706 -0.956891 -0.210898 +-0.293668 -0.950362 -0.102818 +-0.199706 -0.956891 -0.210898 +-0.686198 -0.460064 -0.563448 +-0.686198 -0.460064 -0.563448 +-0.906193 -0.386266 -0.172083 +-0.293668 -0.950362 -0.102818 +0.278630 -0.944534 0.173843 +0.437377 -0.898427 0.039117 +0.876796 -0.404449 0.260095 +0.876796 -0.404449 0.260095 +0.472043 -0.840449 -0.266122 +0.278630 -0.944534 0.173843 +0.000000 -0.903393 0.428813 +-0.058021 -0.917041 0.394549 +-0.134000 -0.341445 0.930301 +-0.134000 -0.341445 0.930301 +0.000000 -0.335574 0.942014 +0.000000 -0.903393 0.428813 +0.161326 -0.320071 -0.933557 +0.083860 -0.883048 -0.461729 +0.000000 -0.902777 -0.430109 +0.000000 -0.902777 -0.430109 +-0.000000 -0.335181 -0.942154 +0.161326 -0.320071 -0.933557 +-0.629331 -0.383170 0.676108 +-0.219047 -0.944662 0.244197 +-0.378489 -0.922436 0.076533 +-0.378489 -0.922436 0.076533 +-0.924386 -0.345298 0.162109 +-0.629331 -0.383170 0.676108 +0.922754 -0.317517 -0.218422 +0.466777 -0.877351 -0.111237 +0.334821 -0.862576 -0.379284 +0.334821 -0.862576 -0.379284 +0.628452 -0.312262 -0.712418 +0.922754 -0.317517 -0.218422 +-0.126855 -0.942566 -0.308993 +-0.053947 -0.933079 -0.355602 +-0.145080 -0.399992 -0.904963 +-0.145080 -0.399992 -0.904963 +-0.391985 -0.437360 -0.809360 +-0.126855 -0.942566 -0.308993 +0.204871 -0.931518 0.300504 +0.472043 -0.840449 -0.266122 +0.016761 -0.961573 0.274037 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.960502 0.278273 +0.016761 -0.961573 0.274037 +0.016761 -0.961573 0.274037 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.016761 -0.961573 0.274037 +0.000000 -0.999997 -0.002593 +0.000000 -0.999997 -0.002593 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.016761 -0.961573 0.274037 +0.000000 -1.000000 0.000002 +0.204871 -0.931518 0.300504 +0.204871 -0.931518 0.300504 +0.278630 -0.944534 0.173843 +0.472043 -0.840449 -0.266122 +-0.000001 -0.480135 -0.877194 +0.000000 -0.999997 -0.002593 +0.016761 -0.961573 0.274037 +0.016761 -0.961573 0.274037 +0.472043 -0.840449 -0.266122 +-0.000001 -0.480135 -0.877194 +0.293668 -0.950362 -0.102818 +-0.437377 -0.898427 0.039117 +-0.466777 -0.877352 -0.111236 +-0.466777 -0.877352 -0.111236 +0.378489 -0.922436 0.076533 +0.293668 -0.950362 -0.102818 +-0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.053947 -0.933079 -0.355603 +0.053947 -0.933079 -0.355603 +0.000000 -0.928568 -0.371161 +-0.000000 -1.000000 0.000002 +-0.083860 -0.883048 -0.461729 +0.058021 -0.917041 0.394549 +0.219047 -0.944662 0.244196 +0.219047 -0.944662 0.244196 +-0.334821 -0.862576 -0.379285 +-0.083860 -0.883048 -0.461729 +-0.278630 -0.944534 0.173843 +0.199706 -0.956891 -0.210898 +0.126855 -0.942566 -0.308993 +0.126855 -0.942566 -0.308993 +-0.204871 -0.931518 0.300504 +-0.278630 -0.944534 0.173843 +-0.437377 -0.898427 0.039117 +0.293668 -0.950362 -0.102818 +0.199706 -0.956891 -0.210898 +0.199706 -0.956891 -0.210898 +-0.278630 -0.944534 0.173843 +-0.437377 -0.898427 0.039117 +0.000000 -0.902777 -0.430109 +0.000000 -0.903393 0.428813 +0.058021 -0.917041 0.394549 +0.058021 -0.917041 0.394549 +-0.083860 -0.883048 -0.461729 +0.000000 -0.902777 -0.430109 +0.219047 -0.944662 0.244196 +0.378489 -0.922436 0.076533 +-0.466777 -0.877352 -0.111236 +-0.466777 -0.877352 -0.111236 +-0.334821 -0.862576 -0.379285 +0.219047 -0.944662 0.244196 +-0.204871 -0.931518 0.300504 +0.126855 -0.942566 -0.308993 +0.053947 -0.933079 -0.355603 +0.053947 -0.933079 -0.355603 +0.000000 -1.000000 0.000002 +-0.204871 -0.931518 0.300504 +0.984855 -0.000001 0.173382 +0.973923 0.000000 -0.226877 +0.906193 -0.386266 -0.172082 +0.906193 -0.386266 -0.172082 +0.924386 -0.345297 0.162111 +0.984855 -0.000001 0.173382 +-0.965948 0.000000 0.258737 +-0.972507 0.000000 -0.232875 +-0.922754 -0.317518 -0.218422 +-0.922754 -0.317518 -0.218422 +-0.876796 -0.404449 0.260094 +-0.965948 0.000000 0.258737 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 0.000000 1.000000 +0.165253 0.000000 -0.986251 +0.000000 0.000000 -1.000000 +0.000000 -0.389580 -0.920992 +0.000000 -0.389580 -0.920992 +0.145080 -0.399992 -0.904963 +0.165253 0.000000 -0.986251 +-0.661497 0.000000 -0.749948 +-0.174458 0.000000 -0.984665 +-0.161326 -0.320071 -0.933557 +-0.161326 -0.320071 -0.933557 +-0.628452 -0.312262 -0.712418 +-0.661497 0.000000 -0.749948 +0.139943 0.000000 0.990160 +0.682761 -0.000001 0.730642 +0.629330 -0.383170 0.676110 +0.629330 -0.383170 0.676110 +0.134000 -0.341445 0.930301 +0.139943 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.865983 0.000000 -0.500074 +-0.472044 -0.840449 -0.266122 +-0.472044 -0.840449 -0.266122 +0.000001 -0.480135 -0.877194 +0.000000 0.000000 -1.000000 +0.973923 0.000000 -0.226877 +0.766123 0.000000 -0.642694 +0.686198 -0.460064 -0.563448 +0.686198 -0.460064 -0.563448 +0.906193 -0.386266 -0.172082 +0.973923 0.000000 -0.226877 +-0.865983 0.000000 -0.500074 +-0.965948 0.000000 0.258737 +-0.876796 -0.404449 0.260094 +-0.876796 -0.404449 0.260094 +-0.472044 -0.840449 -0.266122 +-0.865983 0.000000 -0.500074 +0.000000 0.000000 1.000000 +0.139943 0.000000 0.990160 +0.134000 -0.341445 0.930301 +0.134000 -0.341445 0.930301 +0.000000 -0.335574 0.942014 +0.000000 0.000000 1.000000 +-0.174458 0.000000 -0.984665 +0.000000 0.000000 -1.000000 +-0.000000 -0.335181 -0.942154 +-0.000000 -0.335181 -0.942154 +-0.161326 -0.320071 -0.933557 +-0.174458 0.000000 -0.984665 +-0.972507 0.000000 -0.232875 +-0.661497 0.000000 -0.749948 +-0.628452 -0.312262 -0.712418 +-0.628452 -0.312262 -0.712418 +-0.922754 -0.317518 -0.218422 +-0.972507 0.000000 -0.232875 +0.682761 -0.000001 0.730642 +0.984855 -0.000001 0.173382 +0.924386 -0.345297 0.162111 +0.924386 -0.345297 0.162111 +0.629330 -0.383170 0.676110 +0.682761 -0.000001 0.730642 +0.446771 0.000000 -0.894648 +0.165253 0.000000 -0.986251 +0.145080 -0.399992 -0.904963 +0.145080 -0.399992 -0.904963 +0.391985 -0.437360 -0.809360 +0.446771 0.000000 -0.894648 +0.766123 0.000000 -0.642694 +0.446771 0.000000 -0.894648 +0.391985 -0.437360 -0.809360 +0.391985 -0.437360 -0.809360 +0.686198 -0.460064 -0.563448 +0.766123 0.000000 -0.642694 +-0.437377 -0.898427 0.039117 +-0.876796 -0.404449 0.260094 +-0.922754 -0.317518 -0.218422 +-0.922754 -0.317518 -0.218422 +-0.466777 -0.877352 -0.111236 +-0.437377 -0.898427 0.039117 +0.378489 -0.922436 0.076533 +0.924386 -0.345297 0.162111 +0.906193 -0.386266 -0.172082 +0.906193 -0.386266 -0.172082 +0.293668 -0.950362 -0.102818 +0.378489 -0.922436 0.076533 +0.000000 -0.960502 0.278273 +-0.016761 -0.961573 0.274037 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000002 +0.000000 -0.960502 0.278273 +0.145080 -0.399992 -0.904963 +0.000000 -0.389580 -0.920992 +0.000000 -0.928568 -0.371161 +0.000000 -0.928568 -0.371161 +0.053947 -0.933079 -0.355603 +0.145080 -0.399992 -0.904963 +0.058021 -0.917041 0.394549 +0.134000 -0.341445 0.930301 +0.629330 -0.383170 0.676110 +0.629330 -0.383170 0.676110 +0.219047 -0.944662 0.244196 +0.058021 -0.917041 0.394549 +-0.334821 -0.862576 -0.379285 +-0.628452 -0.312262 -0.712418 +-0.161326 -0.320071 -0.933557 +-0.161326 -0.320071 -0.933557 +-0.083860 -0.883048 -0.461729 +-0.334821 -0.862576 -0.379285 +0.199706 -0.956891 -0.210898 +0.686198 -0.460064 -0.563448 +0.391985 -0.437360 -0.809360 +0.391985 -0.437360 -0.809360 +0.126855 -0.942566 -0.308993 +0.199706 -0.956891 -0.210898 +0.293668 -0.950362 -0.102818 +0.906193 -0.386266 -0.172082 +0.686198 -0.460064 -0.563448 +0.686198 -0.460064 -0.563448 +0.199706 -0.956891 -0.210898 +0.293668 -0.950362 -0.102818 +-0.278630 -0.944534 0.173843 +-0.472044 -0.840449 -0.266122 +-0.876796 -0.404449 0.260094 +-0.876796 -0.404449 0.260094 +-0.437377 -0.898427 0.039117 +-0.278630 -0.944534 0.173843 +0.000000 -0.903393 0.428813 +0.000000 -0.335574 0.942014 +0.134000 -0.341445 0.930301 +0.134000 -0.341445 0.930301 +0.058021 -0.917041 0.394549 +0.000000 -0.903393 0.428813 +-0.161326 -0.320071 -0.933557 +-0.000000 -0.335181 -0.942154 +0.000000 -0.902777 -0.430109 +0.000000 -0.902777 -0.430109 +-0.083860 -0.883048 -0.461729 +-0.161326 -0.320071 -0.933557 +0.629330 -0.383170 0.676110 +0.924386 -0.345297 0.162111 +0.378489 -0.922436 0.076533 +0.378489 -0.922436 0.076533 +0.219047 -0.944662 0.244196 +0.629330 -0.383170 0.676110 +-0.922754 -0.317518 -0.218422 +-0.628452 -0.312262 -0.712418 +-0.334821 -0.862576 -0.379285 +-0.334821 -0.862576 -0.379285 +-0.466777 -0.877352 -0.111236 +-0.922754 -0.317518 -0.218422 +0.126855 -0.942566 -0.308993 +0.391985 -0.437360 -0.809360 +0.145080 -0.399992 -0.904963 +0.145080 -0.399992 -0.904963 +0.053947 -0.933079 -0.355603 +0.126855 -0.942566 -0.308993 +-0.204871 -0.931518 0.300504 +-0.016761 -0.961573 0.274037 +-0.472044 -0.840449 -0.266122 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +-0.016761 -0.961573 0.274037 +-0.016761 -0.961573 0.274037 +0.000000 -0.960502 0.278273 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.999997 -0.002593 +0.000000 -0.999997 -0.002593 +-0.016761 -0.961573 0.274037 +0.000000 -0.482408 0.875946 +-0.016761 -0.961573 0.274037 +-0.204871 -0.931518 0.300504 +0.000000 -1.000000 0.000002 +-0.204871 -0.931518 0.300504 +-0.472044 -0.840449 -0.266122 +-0.278630 -0.944534 0.173843 +0.000001 -0.480135 -0.877194 +-0.472044 -0.840449 -0.266122 +-0.016761 -0.961573 0.274037 +-0.016761 -0.961573 0.274037 +0.000000 -0.999997 -0.002593 +0.000001 -0.480135 -0.877194 +0.159831 -0.985228 -0.061474 +0.159831 -0.985228 -0.061474 +0.705588 -0.705377 -0.067746 +0.705588 -0.705377 -0.067746 +0.705588 -0.705376 -0.067746 +0.159831 -0.985228 -0.061474 +0.987087 -0.160182 0.000001 +0.974743 -0.158179 0.157659 +0.700074 -0.696893 0.155682 +0.700074 -0.696893 0.155682 +0.707107 -0.707107 0.000000 +0.987087 -0.160182 0.000001 +0.705588 -0.705377 -0.067746 +0.985935 -0.159933 -0.048523 +0.985934 -0.159933 -0.048522 +0.985934 -0.159933 -0.048522 +0.705588 -0.705376 -0.067746 +0.705588 -0.705377 -0.067746 +0.707107 -0.707107 0.000000 +0.700074 -0.696893 0.155682 +0.155746 -0.975487 0.155460 +0.155746 -0.975487 0.155460 +0.160182 -0.987087 0.000000 +0.707107 -0.707107 0.000000 +0.155927 -0.141040 0.977647 +0.018551 -0.170483 0.985186 +0.107470 -0.721820 0.683686 +0.107470 -0.721820 0.683686 +0.541661 -0.532698 0.650258 +0.155927 -0.141040 0.977647 +0.173478 -0.024209 0.984540 +0.155927 -0.141040 0.977647 +0.541661 -0.532698 0.650258 +0.541661 -0.532698 0.650258 +0.720099 -0.114166 0.684415 +0.173478 -0.024209 0.984540 +0.541661 -0.532698 0.650258 +0.107470 -0.721820 0.683686 +0.155746 -0.975487 0.155460 +0.155746 -0.975487 0.155460 +0.700074 -0.696893 0.155682 +0.541661 -0.532698 0.650258 +0.720099 -0.114166 0.684415 +0.541661 -0.532698 0.650258 +0.700074 -0.696893 0.155682 +0.700074 -0.696893 0.155682 +0.974743 -0.158179 0.157659 +0.720099 -0.114166 0.684415 +0.902713 -0.144766 -0.405157 +0.645117 -0.643053 -0.412683 +0.456612 -0.453865 -0.765188 +0.456612 -0.453865 -0.765188 +0.676471 -0.107126 -0.728637 +0.902713 -0.144766 -0.405157 +0.456612 -0.453865 -0.765188 +0.645117 -0.643053 -0.412683 +0.144762 -0.898824 -0.413714 +0.144762 -0.898824 -0.413714 +0.107386 -0.671902 -0.732814 +0.456612 -0.453865 -0.765188 +0.676471 -0.107126 -0.728637 +0.692241 0.000000 -0.721666 +0.911793 0.000000 -0.410650 +0.911793 0.000000 -0.410650 +0.902713 -0.144766 -0.405157 +0.676471 -0.107126 -0.728637 +0.911793 0.000000 -0.410650 +0.911793 0.000000 -0.410650 +0.692241 0.000000 -0.721666 +0.692241 0.000000 -0.721666 +0.692242 0.000000 -0.721666 +0.911793 0.000000 -0.410650 +0.000000 0.987087 -0.160182 +0.000000 0.986432 -0.164170 +0.000000 1.000000 0.000000 +0.000000 0.987087 -0.160182 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.987087 -0.160182 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.986432 -0.164170 +0.000000 0.987087 -0.160182 +0.000000 0.707108 -0.707105 +0.000000 0.707108 -0.707105 +0.000000 0.701325 -0.712842 +0.000000 0.986432 -0.164170 +0.000000 0.701325 -0.712842 +0.000000 0.707108 -0.707105 +0.000000 0.160184 -0.987087 +0.000000 0.160184 -0.987087 +0.000000 0.159534 -0.987193 +0.000000 0.701325 -0.712842 +0.000000 0.159534 -0.987193 +0.000000 0.160184 -0.987087 +0.000000 -0.160184 -0.987087 +0.000000 -0.160184 -0.987087 +0.000000 -0.159534 -0.987192 +0.000000 0.159534 -0.987193 +0.000000 -0.160184 -0.987087 +0.000000 -0.707107 -0.707106 +0.000000 -0.701324 -0.712843 +0.000000 -0.701324 -0.712843 +0.000000 -0.159534 -0.987192 +0.000000 -0.160184 -0.987087 +0.000000 -0.707107 -0.707106 +0.000000 -0.987087 -0.160183 +0.000000 -0.986432 -0.164171 +0.000000 -0.986432 -0.164171 +0.000000 -0.701324 -0.712843 +0.000000 -0.707107 -0.707106 +0.000000 -0.686823 -0.726825 +0.000000 -0.906973 -0.421189 +0.000000 -0.906973 -0.421189 +0.000000 -0.906973 -0.421189 +0.000000 -0.686823 -0.726825 +0.000000 -0.686823 -0.726825 +0.000000 -0.906973 -0.421189 +0.000000 -0.686823 -0.726825 +0.107386 -0.671902 -0.732814 +0.107386 -0.671902 -0.732814 +0.144762 -0.898824 -0.413714 +0.000000 -0.906973 -0.421189 +-0.160183 0.000000 -0.987087 +-0.707108 0.000000 -0.707105 +-0.699024 0.000000 -0.715098 +-0.699024 0.000000 -0.715098 +-0.159277 0.000000 -0.987234 +-0.160183 0.000000 -0.987087 +-0.707108 0.000000 -0.707105 +-0.987088 0.000000 -0.160181 +-0.986171 0.000000 -0.165730 +-0.986171 0.000000 -0.165730 +-0.699024 0.000000 -0.715098 +-0.707108 0.000000 -0.707105 +0.987088 0.000000 -0.160181 +0.986171 0.000000 -0.165731 +1.000000 0.000000 0.000000 +0.987088 0.000000 -0.160181 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.987088 0.000000 -0.160181 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.986171 0.000000 -0.165731 +0.987088 0.000000 -0.160181 +0.707109 0.000000 -0.707105 +0.707109 0.000000 -0.707105 +0.699024 0.000000 -0.715098 +0.986171 0.000000 -0.165731 +0.699024 0.000000 -0.715098 +0.707109 0.000000 -0.707105 +0.160184 0.000000 -0.987087 +0.160184 0.000000 -0.987087 +0.159277 0.000000 -0.987234 +0.699024 0.000000 -0.715098 +0.159277 0.000000 -0.987234 +0.160184 0.000000 -0.987087 +-0.160183 0.000000 -0.987087 +-0.160183 0.000000 -0.987087 +-0.159277 0.000000 -0.987234 +0.159277 0.000000 -0.987234 +0.987396 0.000000 0.158268 +0.709858 0.000000 0.704345 +0.720099 -0.114166 0.684415 +0.720099 -0.114166 0.684415 +0.974743 -0.158179 0.157659 +0.987396 0.000000 0.158268 +0.709858 0.000000 0.704345 +0.162115 0.000000 0.986772 +0.173478 -0.024209 0.984540 +0.173478 -0.024209 0.984540 +0.720099 -0.114166 0.684415 +0.709858 0.000000 0.704345 +0.162115 0.000000 0.986772 +0.709858 0.000000 0.704345 +0.709857 0.000000 0.704345 +0.709857 0.000000 0.704345 +0.162115 0.000000 0.986772 +0.162115 0.000000 0.986772 +-0.000000 -0.707107 0.707106 +0.000000 -0.707109 0.707105 +0.000000 -0.987088 0.160181 +0.000000 -0.987088 0.160181 +-0.000001 -0.987087 0.160183 +-0.000000 -0.707107 0.707106 +0.000000 -0.160184 0.987087 +0.000000 -0.707109 0.707105 +-0.000000 -0.707107 0.707106 +-0.000000 -0.707107 0.707106 +0.000000 -0.160183 0.987087 +0.000000 -0.160184 0.987087 +-0.000000 0.160183 0.987087 +0.000000 -0.160184 0.987087 +0.000000 -0.160183 0.987087 +0.000000 -0.160183 0.987087 +-0.000000 0.160183 0.987087 +-0.000000 0.160183 0.987087 +-0.000000 0.707107 0.707106 +-0.000000 0.160183 0.987087 +-0.000000 0.160183 0.987087 +-0.000000 0.160183 0.987087 +-0.000000 0.707107 0.707106 +-0.000000 0.707107 0.707106 +-0.000001 0.987087 0.160183 +-0.000000 0.707107 0.707106 +-0.000000 0.707107 0.707106 +-0.000000 0.707107 0.707106 +-0.000001 0.987087 0.160183 +-0.000001 0.987087 0.160183 +0.000000 -0.987396 0.158267 +0.000000 -0.987396 0.158267 +0.000000 -0.709859 0.704344 +0.000000 -0.709859 0.704344 +0.000000 -0.709859 0.704344 +0.000000 -0.987396 0.158267 +0.000000 -0.709859 0.704344 +0.000000 -0.709859 0.704344 +0.000000 -0.162115 0.986772 +0.000000 -0.162115 0.986772 +0.000000 -0.162115 0.986772 +0.000000 -0.709859 0.704344 +0.000000 -0.987396 0.158267 +0.155746 -0.975487 0.155460 +0.107470 -0.721820 0.683686 +0.107470 -0.721820 0.683686 +0.000000 -0.709858 0.704344 +0.000000 -0.987396 0.158267 +0.018551 -0.170483 0.985186 +0.000000 -0.162115 0.986772 +0.000000 -0.709858 0.704344 +0.000000 -0.709858 0.704344 +0.107470 -0.721820 0.683686 +0.018551 -0.170483 0.985186 +-0.160184 0.000000 0.987087 +-0.707107 0.000000 0.707106 +-0.707107 0.000000 0.707106 +-0.707107 0.000000 0.707106 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.707108 0.000001 0.707105 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.707108 0.000000 0.707106 +0.707108 0.000001 0.707105 +0.987087 0.000000 0.160183 +0.987088 0.000001 0.160180 +0.707108 0.000001 0.707105 +0.707108 0.000001 0.707105 +0.707108 0.000000 0.707106 +0.987087 0.000000 0.160183 +-0.707107 0.000000 0.707106 +-0.987087 0.000000 0.160183 +-0.987087 0.000000 0.160183 +-0.987087 0.000000 0.160183 +-0.707107 0.000000 0.707106 +-0.707107 0.000000 0.707106 +0.911793 0.000000 -0.410650 +0.999196 -0.000000 -0.040096 +0.999195 -0.000005 -0.040120 +0.999195 -0.000005 -0.040120 +0.911793 0.000000 -0.410650 +0.911793 0.000000 -0.410650 +0.000000 -1.000000 0.000000 +0.000000 -0.986432 -0.164171 +0.000000 -0.987087 -0.160183 +0.000000 -0.987087 -0.160183 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.987087 -0.160183 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000001 -0.998442 -0.055795 +0.000000 -0.998442 -0.055795 +0.000000 -0.999610 -0.027908 +0.000000 -0.999610 -0.027908 +0.000000 -0.999611 -0.027908 +0.000001 -0.998442 -0.055795 +-1.000000 0.000000 0.000000 +-0.986171 0.000000 -0.165730 +-0.987088 0.000000 -0.160181 +-0.987088 0.000000 -0.160181 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987088 0.000000 -0.160181 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +1.000000 -0.000000 0.000001 +0.999799 -0.000000 -0.020062 +0.999799 0.000000 -0.020063 +0.999799 0.000000 -0.020063 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000001 +-0.000001 -0.987087 0.160183 +0.000000 -0.987088 0.160181 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +-0.000001 -0.987087 0.160183 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +-0.000001 1.000000 -0.000000 +-0.000001 0.987087 0.160183 +-0.000001 0.987087 0.160183 +-0.000001 1.000000 -0.000000 +-0.000001 0.987087 0.160183 +-0.000000 1.000000 0.000000 +-0.000001 1.000000 -0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000001 +-0.000001 1.000000 -0.000000 +-0.000000 1.000000 0.000001 +-0.000001 1.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.160182 -0.987087 0.000000 +0.155746 -0.975487 0.155460 +0.000000 -0.987396 0.158267 +0.000000 -0.987396 0.158267 +0.000000 -1.000000 0.000000 +0.160182 -0.987087 0.000000 +0.987087 0.000000 0.160183 +1.000000 0.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000001 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.987088 0.000001 0.160180 +0.987087 0.000000 0.160183 +1.000000 0.000000 -0.000000 +0.987088 0.000001 0.160180 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987087 0.000000 0.160183 +-1.000000 0.000000 0.000000 +-0.987087 0.000000 0.160183 +-0.987087 0.000000 0.160183 +-1.000000 0.000000 0.000000 +-0.987087 0.000000 0.160183 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.987396 0.000000 0.158268 +0.987396 0.000000 0.158268 +0.709857 0.000000 0.704345 +0.709857 0.000000 0.704345 +0.709858 0.000000 0.704345 +0.987396 0.000000 0.158268 +0.000000 0.000000 1.000000 +0.000000 -0.162115 0.986772 +0.018551 -0.170483 0.985186 +0.000000 0.000000 1.000000 +0.018551 -0.170483 0.985186 +0.173478 -0.024209 0.984540 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.173478 -0.024209 0.984540 +0.000000 0.000000 1.000000 +0.173478 -0.024209 0.984540 +0.162115 0.000000 0.986772 +0.173478 -0.024209 0.984540 +0.018551 -0.170483 0.985186 +0.155927 -0.141040 0.977647 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.162115 0.986772 +0.000000 -0.162115 0.986772 +0.000000 -0.162115 0.986772 +0.000000 0.000000 1.000000 +0.999195 0.000000 -0.040116 +0.999195 -0.000000 -0.040116 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999195 0.000000 -0.040116 +0.999799 0.000000 -0.020062 +1.000000 -0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999195 0.000000 -0.040118 +0.999195 0.000000 -0.040117 +0.985934 -0.159933 -0.048522 +0.985934 -0.159933 -0.048522 +0.985935 -0.159933 -0.048523 +0.999195 0.000000 -0.040118 +0.974743 -0.158179 0.157659 +0.987087 -0.160182 0.000001 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.987396 0.000000 0.158268 +0.974743 -0.158179 0.157659 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +1.000000 0.000000 0.000001 +0.999799 0.000000 -0.020062 +0.999195 0.000000 -0.040117 +0.999195 0.000000 -0.040116 +0.999195 0.000000 -0.040116 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999195 -0.000000 -0.040116 +0.999195 -0.000001 -0.040116 +0.999799 -0.000000 -0.020062 +0.999799 -0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999195 -0.000000 -0.040116 +0.999799 -0.000000 -0.020062 +1.000000 -0.000000 0.000001 +1.000000 -0.000000 0.000001 +1.000000 -0.000000 0.000001 +0.999799 0.000000 -0.020062 +0.999799 -0.000000 -0.020062 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000001 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000000 +0.999195 -0.000001 -0.040116 +0.999195 -0.000005 -0.040120 +0.999196 -0.000000 -0.040096 +0.999196 -0.000000 -0.040096 +0.999196 -0.000000 -0.040095 +0.999195 -0.000001 -0.040116 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000000 +0.987087 -0.160182 0.000001 +0.987087 -0.160182 0.000001 +0.987087 -0.160182 0.000000 +1.000000 0.000000 0.000001 +0.987087 -0.160182 0.000000 +0.987087 -0.160182 0.000001 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000001 +0.987087 -0.160182 0.000000 +0.707107 -0.707107 0.000001 +0.707107 -0.707107 0.000000 +0.160182 -0.987087 0.000000 +0.160182 -0.987087 0.000000 +0.160183 -0.987087 0.000000 +0.707107 -0.707107 0.000001 +0.160183 -0.987087 0.000000 +0.160182 -0.987087 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.160183 -0.987087 0.000000 +1.000000 0.000000 0.000001 +0.987087 -0.160182 0.000000 +0.986399 -0.162556 -0.024328 +0.986399 -0.162556 -0.024328 +0.999799 0.000000 -0.020062 +1.000000 0.000000 0.000001 +0.986399 -0.162556 -0.024328 +0.987087 -0.160182 0.000000 +0.707107 -0.707107 0.000001 +0.707107 -0.707107 0.000001 +0.705633 -0.707781 -0.033587 +0.986399 -0.162556 -0.024328 +0.705633 -0.707781 -0.033587 +0.707107 -0.707107 0.000001 +0.160183 -0.987087 0.000000 +0.160183 -0.987087 0.000000 +0.161626 -0.986374 -0.030703 +0.705633 -0.707781 -0.033587 +0.000000 -0.999611 -0.027908 +0.000000 -0.999610 -0.027908 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.999611 -0.027908 +0.000001 -0.998442 -0.055795 +0.000000 -0.999611 -0.027908 +0.000000 -0.999610 -0.027908 +0.000000 -0.999610 -0.027908 +-0.000001 -0.998442 -0.055795 +0.000001 -0.998442 -0.055795 +0.000000 -0.999610 -0.027908 +0.000000 -0.999611 -0.027908 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.999610 -0.027908 +0.161626 -0.986374 -0.030703 +0.160183 -0.987087 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.999610 -0.027908 +0.161626 -0.986374 -0.030703 +0.159831 -0.985228 -0.061474 +0.000000 -0.998442 -0.055795 +0.000000 -0.998442 -0.055794 +0.000000 -0.998442 -0.055794 +0.159831 -0.985228 -0.061474 +0.159831 -0.985228 -0.061474 +0.000000 -0.999610 -0.027908 +0.000000 -0.998442 -0.055795 +0.159831 -0.985228 -0.061474 +0.159831 -0.985228 -0.061474 +0.161626 -0.986374 -0.030703 +0.000000 -0.999610 -0.027908 +0.161626 -0.986374 -0.030703 +0.159831 -0.985228 -0.061474 +0.705588 -0.705376 -0.067746 +0.705588 -0.705376 -0.067746 +0.705633 -0.707781 -0.033587 +0.161626 -0.986374 -0.030703 +0.705588 -0.705376 -0.067746 +0.985934 -0.159933 -0.048522 +0.986399 -0.162556 -0.024328 +0.986399 -0.162556 -0.024328 +0.705633 -0.707781 -0.033587 +0.705588 -0.705376 -0.067746 +0.999195 0.000000 -0.040117 +0.999799 0.000000 -0.020062 +0.986399 -0.162556 -0.024328 +0.986399 -0.162556 -0.024328 +0.985934 -0.159933 -0.048522 +0.999195 0.000000 -0.040117 +0.999195 0.000000 -0.040118 +0.985935 -0.159933 -0.048523 +0.902713 -0.144766 -0.405157 +0.902713 -0.144766 -0.405157 +0.911793 0.000000 -0.410650 +0.999195 0.000000 -0.040118 +0.985935 -0.159933 -0.048523 +0.705588 -0.705377 -0.067746 +0.645117 -0.643053 -0.412683 +0.645117 -0.643053 -0.412683 +0.902713 -0.144766 -0.405157 +0.985935 -0.159933 -0.048523 +0.645117 -0.643053 -0.412683 +0.705588 -0.705377 -0.067746 +0.159831 -0.985228 -0.061474 +0.159831 -0.985228 -0.061474 +0.144762 -0.898824 -0.413714 +0.645117 -0.643053 -0.412683 +0.144762 -0.898824 -0.413714 +0.159831 -0.985228 -0.061474 +0.000000 -0.998442 -0.055794 +0.000000 -0.998442 -0.055794 +0.000000 -0.906973 -0.421189 +0.144762 -0.898824 -0.413714 +-0.000000 -0.998441 -0.055810 +0.000005 -0.998442 -0.055795 +0.000001 -0.999610 -0.027908 +0.000001 -0.999610 -0.027908 +0.000000 -0.999611 -0.027905 +-0.000000 -0.998441 -0.055810 +0.000000 -0.987396 0.158267 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.987396 0.158267 +0.000000 -0.987396 0.158267 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000001 -0.999610 -0.027908 +0.000001 -0.999610 -0.027908 +0.000000 -0.999610 -0.027908 +0.000000 -1.000000 0.000000 +0.000001 -0.999610 -0.027908 +0.000005 -0.998442 -0.055795 +-0.000001 -0.998442 -0.055795 +-0.000001 -0.998442 -0.055795 +0.000000 -0.999610 -0.027908 +0.000001 -0.999610 -0.027908 +0.000002 -0.998442 -0.055798 +0.000005 -0.998442 -0.055795 +-0.000000 -0.998441 -0.055810 +-0.000000 -0.998441 -0.055810 +-0.000000 -0.998441 -0.055815 +0.000002 -0.998442 -0.055798 +0.000002 -0.998442 -0.055798 +-0.000000 -0.998441 -0.055815 +0.000000 -0.906973 -0.421189 +0.000000 -0.906973 -0.421189 +0.000000 -0.906973 -0.421189 +0.000002 -0.998442 -0.055798 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.999611 -0.027905 +0.000000 -0.999611 -0.027905 +0.000001 -0.999610 -0.027908 +0.000000 -1.000000 0.000000 +0.987396 0.000000 0.158268 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +0.987396 0.000000 0.158268 +0.987396 0.000000 0.158268 +0.999195 -0.000001 -0.040116 +0.999196 -0.000000 -0.040095 +0.999799 0.000000 -0.020063 +0.999799 0.000000 -0.020063 +0.999799 -0.000000 -0.020062 +0.999195 -0.000001 -0.040116 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000001 +0.000000 -1.000000 -0.000001 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000003 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000001 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000003 +-0.000000 -1.000000 0.000003 +0.000000 -1.000000 0.000021 +-0.000000 -1.000000 0.000001 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.293667 -0.950362 -0.102818 +-0.437377 -0.898427 0.039117 +-0.466777 -0.877351 -0.111237 +-0.466777 -0.877351 -0.111237 +0.378489 -0.922436 0.076533 +0.293667 -0.950362 -0.102818 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.053947 -0.933079 -0.355603 +0.053947 -0.933079 -0.355603 +0.000000 -0.928568 -0.371161 +0.000000 -1.000000 0.000002 +-0.083860 -0.883048 -0.461729 +0.058021 -0.917041 0.394549 +0.219047 -0.944662 0.244197 +0.219047 -0.944662 0.244197 +-0.334821 -0.862577 -0.379284 +-0.083860 -0.883048 -0.461729 +-0.278630 -0.944534 0.173843 +0.199706 -0.956891 -0.210898 +0.126855 -0.942566 -0.308994 +0.126855 -0.942566 -0.308994 +-0.204871 -0.931518 0.300504 +-0.278630 -0.944534 0.173843 +-0.437377 -0.898427 0.039117 +0.293667 -0.950362 -0.102818 +0.199706 -0.956891 -0.210898 +0.199706 -0.956891 -0.210898 +-0.278630 -0.944534 0.173843 +-0.437377 -0.898427 0.039117 +0.000000 -0.902777 -0.430109 +-0.000000 -0.903393 0.428813 +0.058021 -0.917041 0.394549 +0.058021 -0.917041 0.394549 +-0.083860 -0.883048 -0.461729 +0.000000 -0.902777 -0.430109 +0.219047 -0.944662 0.244197 +0.378489 -0.922436 0.076533 +-0.466777 -0.877351 -0.111237 +-0.466777 -0.877351 -0.111237 +-0.334821 -0.862577 -0.379284 +0.219047 -0.944662 0.244197 +-0.204871 -0.931518 0.300504 +0.126855 -0.942566 -0.308994 +0.053947 -0.933079 -0.355603 +0.053947 -0.933079 -0.355603 +0.000000 -1.000000 0.000002 +-0.204871 -0.931518 0.300504 +0.984855 -0.000001 0.173380 +0.973923 0.000000 -0.226877 +0.906193 -0.386267 -0.172082 +0.906193 -0.386267 -0.172082 +0.924386 -0.345298 0.162108 +0.984855 -0.000001 0.173380 +-0.965948 0.000000 0.258737 +-0.972507 0.000000 -0.232874 +-0.922754 -0.317517 -0.218422 +-0.922754 -0.317517 -0.218422 +-0.876796 -0.404449 0.260095 +-0.965948 0.000000 0.258737 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 0.000000 1.000000 +0.165253 0.000000 -0.986251 +0.000000 0.000000 -1.000000 +0.000000 -0.389580 -0.920992 +0.000000 -0.389580 -0.920992 +0.145080 -0.399992 -0.904963 +0.165253 0.000000 -0.986251 +-0.661497 0.000000 -0.749948 +-0.174458 0.000000 -0.984665 +-0.161327 -0.320071 -0.933557 +-0.161327 -0.320071 -0.933557 +-0.628453 -0.312262 -0.712418 +-0.661497 0.000000 -0.749948 +0.139943 0.000000 0.990160 +0.682763 -0.000001 0.730640 +0.629331 -0.383170 0.676109 +0.629331 -0.383170 0.676109 +0.134000 -0.341445 0.930301 +0.139943 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.865983 0.000000 -0.500074 +-0.472044 -0.840449 -0.266121 +-0.472044 -0.840449 -0.266121 +0.000001 -0.480135 -0.877194 +0.000000 0.000000 -1.000000 +0.973923 0.000000 -0.226877 +0.766123 0.000000 -0.642694 +0.686198 -0.460064 -0.563448 +0.686198 -0.460064 -0.563448 +0.906193 -0.386267 -0.172082 +0.973923 0.000000 -0.226877 +-0.865983 0.000000 -0.500074 +-0.965948 0.000000 0.258737 +-0.876796 -0.404449 0.260095 +-0.876796 -0.404449 0.260095 +-0.472044 -0.840449 -0.266121 +-0.865983 0.000000 -0.500074 +-0.000000 0.000000 1.000000 +0.139943 0.000000 0.990160 +0.134000 -0.341445 0.930301 +0.134000 -0.341445 0.930301 +-0.000000 -0.335574 0.942014 +-0.000000 0.000000 1.000000 +-0.174458 0.000000 -0.984665 +0.000000 0.000000 -1.000000 +-0.000000 -0.335182 -0.942154 +-0.000000 -0.335182 -0.942154 +-0.161327 -0.320071 -0.933557 +-0.174458 0.000000 -0.984665 +-0.972507 0.000000 -0.232874 +-0.661497 0.000000 -0.749948 +-0.628453 -0.312262 -0.712418 +-0.628453 -0.312262 -0.712418 +-0.922754 -0.317517 -0.218422 +-0.972507 0.000000 -0.232874 +0.682763 -0.000001 0.730640 +0.984855 -0.000001 0.173380 +0.924386 -0.345298 0.162108 +0.924386 -0.345298 0.162108 +0.629331 -0.383170 0.676109 +0.682763 -0.000001 0.730640 +0.446772 0.000000 -0.894648 +0.165253 0.000000 -0.986251 +0.145080 -0.399992 -0.904963 +0.145080 -0.399992 -0.904963 +0.391985 -0.437360 -0.809360 +0.446772 0.000000 -0.894648 +0.766123 0.000000 -0.642694 +0.446772 0.000000 -0.894648 +0.391985 -0.437360 -0.809360 +0.391985 -0.437360 -0.809360 +0.686198 -0.460064 -0.563448 +0.766123 0.000000 -0.642694 +-0.437377 -0.898427 0.039117 +-0.876796 -0.404449 0.260095 +-0.922754 -0.317517 -0.218422 +-0.922754 -0.317517 -0.218422 +-0.466777 -0.877351 -0.111237 +-0.437377 -0.898427 0.039117 +0.378489 -0.922436 0.076533 +0.924386 -0.345298 0.162108 +0.906193 -0.386267 -0.172082 +0.906193 -0.386267 -0.172082 +0.293667 -0.950362 -0.102818 +0.378489 -0.922436 0.076533 +0.000000 -0.960502 0.278273 +-0.016761 -0.961573 0.274037 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -0.960502 0.278273 +0.145080 -0.399992 -0.904963 +0.000000 -0.389580 -0.920992 +0.000000 -0.928568 -0.371161 +0.000000 -0.928568 -0.371161 +0.053947 -0.933079 -0.355603 +0.145080 -0.399992 -0.904963 +0.058021 -0.917041 0.394549 +0.134000 -0.341445 0.930301 +0.629331 -0.383170 0.676109 +0.629331 -0.383170 0.676109 +0.219047 -0.944662 0.244197 +0.058021 -0.917041 0.394549 +-0.334821 -0.862577 -0.379284 +-0.628453 -0.312262 -0.712418 +-0.161327 -0.320071 -0.933557 +-0.161327 -0.320071 -0.933557 +-0.083860 -0.883048 -0.461729 +-0.334821 -0.862577 -0.379284 +0.199706 -0.956891 -0.210898 +0.686198 -0.460064 -0.563448 +0.391985 -0.437360 -0.809360 +0.391985 -0.437360 -0.809360 +0.126855 -0.942566 -0.308994 +0.199706 -0.956891 -0.210898 +0.293667 -0.950362 -0.102818 +0.906193 -0.386267 -0.172082 +0.686198 -0.460064 -0.563448 +0.686198 -0.460064 -0.563448 +0.199706 -0.956891 -0.210898 +0.293667 -0.950362 -0.102818 +-0.278630 -0.944534 0.173843 +-0.472044 -0.840449 -0.266121 +-0.876796 -0.404449 0.260095 +-0.876796 -0.404449 0.260095 +-0.437377 -0.898427 0.039117 +-0.278630 -0.944534 0.173843 +-0.000000 -0.903393 0.428813 +-0.000000 -0.335574 0.942014 +0.134000 -0.341445 0.930301 +0.134000 -0.341445 0.930301 +0.058021 -0.917041 0.394549 +-0.000000 -0.903393 0.428813 +-0.161327 -0.320071 -0.933557 +-0.000000 -0.335182 -0.942154 +0.000000 -0.902777 -0.430109 +0.000000 -0.902777 -0.430109 +-0.083860 -0.883048 -0.461729 +-0.161327 -0.320071 -0.933557 +0.629331 -0.383170 0.676109 +0.924386 -0.345298 0.162108 +0.378489 -0.922436 0.076533 +0.378489 -0.922436 0.076533 +0.219047 -0.944662 0.244197 +0.629331 -0.383170 0.676109 +-0.922754 -0.317517 -0.218422 +-0.628453 -0.312262 -0.712418 +-0.334821 -0.862577 -0.379284 +-0.334821 -0.862577 -0.379284 +-0.466777 -0.877351 -0.111237 +-0.922754 -0.317517 -0.218422 +0.126855 -0.942566 -0.308994 +0.391985 -0.437360 -0.809360 +0.145080 -0.399992 -0.904963 +0.145080 -0.399992 -0.904963 +0.053947 -0.933079 -0.355603 +0.126855 -0.942566 -0.308994 +-0.204871 -0.931518 0.300504 +-0.016761 -0.961573 0.274037 +-0.472044 -0.840449 -0.266121 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +-0.016761 -0.961573 0.274037 +-0.016761 -0.961573 0.274037 +0.000000 -0.960502 0.278273 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.999997 -0.002593 +0.000000 -0.999997 -0.002593 +-0.016761 -0.961573 0.274037 +0.000000 -0.482408 0.875946 +-0.016761 -0.961573 0.274037 +-0.204871 -0.931518 0.300504 +0.000000 -1.000000 0.000002 +-0.204871 -0.931518 0.300504 +-0.472044 -0.840449 -0.266121 +-0.278630 -0.944534 0.173843 +0.000001 -0.480135 -0.877194 +-0.472044 -0.840449 -0.266121 +-0.016761 -0.961573 0.274037 +-0.016761 -0.961573 0.274037 +0.000000 -0.999997 -0.002593 +0.000001 -0.480135 -0.877194 +-0.293669 -0.950361 -0.102818 +-0.378490 -0.922436 0.076533 +0.466777 -0.877352 -0.111236 +0.466777 -0.877352 -0.111236 +0.437376 -0.898427 0.039117 +-0.293669 -0.950361 -0.102818 +0.000000 -1.000000 0.000002 +0.000000 -0.928568 -0.371161 +-0.053947 -0.933079 -0.355603 +-0.053947 -0.933079 -0.355603 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.083860 -0.883048 -0.461729 +0.334821 -0.862576 -0.379284 +-0.219047 -0.944662 0.244197 +-0.219047 -0.944662 0.244197 +-0.058021 -0.917041 0.394549 +0.083860 -0.883048 -0.461729 +0.278630 -0.944534 0.173843 +0.204871 -0.931518 0.300504 +-0.126855 -0.942566 -0.308994 +-0.126855 -0.942566 -0.308994 +-0.199706 -0.956891 -0.210898 +0.278630 -0.944534 0.173843 +0.437376 -0.898427 0.039117 +0.278630 -0.944534 0.173843 +-0.199706 -0.956891 -0.210898 +-0.199706 -0.956891 -0.210898 +-0.293669 -0.950361 -0.102818 +0.437376 -0.898427 0.039117 +0.000000 -0.902777 -0.430109 +0.083860 -0.883048 -0.461729 +-0.058021 -0.917041 0.394549 +-0.058021 -0.917041 0.394549 +-0.000000 -0.903393 0.428813 +0.000000 -0.902777 -0.430109 +-0.219047 -0.944662 0.244197 +0.334821 -0.862576 -0.379284 +0.466777 -0.877352 -0.111236 +0.466777 -0.877352 -0.111236 +-0.378490 -0.922436 0.076533 +-0.219047 -0.944662 0.244197 +0.204871 -0.931518 0.300504 +0.000000 -1.000000 0.000002 +-0.053947 -0.933079 -0.355603 +-0.053947 -0.933079 -0.355603 +-0.126855 -0.942566 -0.308994 +0.204871 -0.931518 0.300504 +-0.984855 0.000000 0.173382 +-0.924387 -0.345297 0.162109 +-0.906194 -0.386265 -0.172082 +-0.906194 -0.386265 -0.172082 +-0.973923 0.000000 -0.226877 +-0.984855 0.000000 0.173382 +0.965948 0.000000 0.258737 +0.876797 -0.404449 0.260094 +0.922754 -0.317518 -0.218422 +0.922754 -0.317518 -0.218422 +0.972507 0.000000 -0.232875 +0.965948 0.000000 0.258737 +0.000000 0.000000 1.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.165253 0.000000 -0.986251 +-0.145080 -0.399992 -0.904963 +0.000000 -0.389580 -0.920992 +0.000000 -0.389580 -0.920992 +0.000000 0.000000 -1.000000 +-0.165253 0.000000 -0.986251 +0.661497 0.000000 -0.749948 +0.628453 -0.312262 -0.712418 +0.161327 -0.320071 -0.933557 +0.161327 -0.320071 -0.933557 +0.174458 0.000000 -0.984665 +0.661497 0.000000 -0.749948 +-0.139942 0.000000 0.990160 +-0.133999 -0.341445 0.930301 +-0.629331 -0.383170 0.676109 +-0.629331 -0.383170 0.676109 +-0.682761 0.000000 0.730642 +-0.139942 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000001 -0.480135 -0.877194 +0.472044 -0.840449 -0.266122 +0.472044 -0.840449 -0.266122 +0.865983 0.000000 -0.500074 +0.000000 0.000000 -1.000000 +-0.973923 0.000000 -0.226877 +-0.906194 -0.386265 -0.172082 +-0.686198 -0.460063 -0.563448 +-0.686198 -0.460063 -0.563448 +-0.766123 0.000000 -0.642694 +-0.973923 0.000000 -0.226877 +0.865983 0.000000 -0.500074 +0.472044 -0.840449 -0.266122 +0.876797 -0.404449 0.260094 +0.876797 -0.404449 0.260094 +0.965948 0.000000 0.258737 +0.865983 0.000000 -0.500074 +-0.000000 0.000000 1.000000 +-0.000000 -0.335574 0.942014 +-0.133999 -0.341445 0.930301 +-0.133999 -0.341445 0.930301 +-0.139942 0.000000 0.990160 +-0.000000 0.000000 1.000000 +0.174458 0.000000 -0.984665 +0.161327 -0.320071 -0.933557 +-0.000000 -0.335182 -0.942154 +-0.000000 -0.335182 -0.942154 +0.000000 0.000000 -1.000000 +0.174458 0.000000 -0.984665 +0.972507 0.000000 -0.232875 +0.922754 -0.317518 -0.218422 +0.628453 -0.312262 -0.712418 +0.628453 -0.312262 -0.712418 +0.661497 0.000000 -0.749948 +0.972507 0.000000 -0.232875 +-0.682761 0.000000 0.730642 +-0.629331 -0.383170 0.676109 +-0.924387 -0.345297 0.162109 +-0.924387 -0.345297 0.162109 +-0.984855 0.000000 0.173382 +-0.682761 0.000000 0.730642 +-0.446771 0.000000 -0.894648 +-0.391985 -0.437360 -0.809361 +-0.145080 -0.399992 -0.904963 +-0.145080 -0.399992 -0.904963 +-0.165253 0.000000 -0.986251 +-0.446771 0.000000 -0.894648 +-0.766123 0.000000 -0.642694 +-0.686198 -0.460063 -0.563448 +-0.391985 -0.437360 -0.809361 +-0.391985 -0.437360 -0.809361 +-0.446771 0.000000 -0.894648 +-0.766123 0.000000 -0.642694 +0.437376 -0.898427 0.039117 +0.466777 -0.877352 -0.111236 +0.922754 -0.317518 -0.218422 +0.922754 -0.317518 -0.218422 +0.876797 -0.404449 0.260094 +0.437376 -0.898427 0.039117 +-0.378490 -0.922436 0.076533 +-0.293669 -0.950361 -0.102818 +-0.906194 -0.386265 -0.172082 +-0.906194 -0.386265 -0.172082 +-0.924387 -0.345297 0.162109 +-0.378490 -0.922436 0.076533 +0.000000 -0.960502 0.278273 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.016761 -0.961573 0.274037 +0.000000 -0.960502 0.278273 +-0.145080 -0.399992 -0.904963 +-0.053947 -0.933079 -0.355603 +0.000000 -0.928568 -0.371161 +0.000000 -0.928568 -0.371161 +0.000000 -0.389580 -0.920992 +-0.145080 -0.399992 -0.904963 +-0.058021 -0.917041 0.394549 +-0.219047 -0.944662 0.244197 +-0.629331 -0.383170 0.676109 +-0.629331 -0.383170 0.676109 +-0.133999 -0.341445 0.930301 +-0.058021 -0.917041 0.394549 +0.334821 -0.862576 -0.379284 +0.083860 -0.883048 -0.461729 +0.161327 -0.320071 -0.933557 +0.161327 -0.320071 -0.933557 +0.628453 -0.312262 -0.712418 +0.334821 -0.862576 -0.379284 +-0.199706 -0.956891 -0.210898 +-0.126855 -0.942566 -0.308994 +-0.391985 -0.437360 -0.809361 +-0.391985 -0.437360 -0.809361 +-0.686198 -0.460063 -0.563448 +-0.199706 -0.956891 -0.210898 +-0.293669 -0.950361 -0.102818 +-0.199706 -0.956891 -0.210898 +-0.686198 -0.460063 -0.563448 +-0.686198 -0.460063 -0.563448 +-0.906194 -0.386265 -0.172082 +-0.293669 -0.950361 -0.102818 +0.278630 -0.944534 0.173843 +0.437376 -0.898427 0.039117 +0.876797 -0.404449 0.260094 +0.876797 -0.404449 0.260094 +0.472044 -0.840449 -0.266122 +0.278630 -0.944534 0.173843 +-0.000000 -0.903393 0.428813 +-0.058021 -0.917041 0.394549 +-0.133999 -0.341445 0.930301 +-0.133999 -0.341445 0.930301 +-0.000000 -0.335574 0.942014 +-0.000000 -0.903393 0.428813 +0.161327 -0.320071 -0.933557 +0.083860 -0.883048 -0.461729 +0.000000 -0.902777 -0.430109 +0.000000 -0.902777 -0.430109 +-0.000000 -0.335182 -0.942154 +0.161327 -0.320071 -0.933557 +-0.629331 -0.383170 0.676109 +-0.219047 -0.944662 0.244197 +-0.378490 -0.922436 0.076533 +-0.378490 -0.922436 0.076533 +-0.924387 -0.345297 0.162109 +-0.629331 -0.383170 0.676109 +0.922754 -0.317518 -0.218422 +0.466777 -0.877352 -0.111236 +0.334821 -0.862576 -0.379284 +0.334821 -0.862576 -0.379284 +0.628453 -0.312262 -0.712418 +0.922754 -0.317518 -0.218422 +-0.126855 -0.942566 -0.308994 +-0.053947 -0.933079 -0.355603 +-0.145080 -0.399992 -0.904963 +-0.145080 -0.399992 -0.904963 +-0.391985 -0.437360 -0.809361 +-0.126855 -0.942566 -0.308994 +0.204871 -0.931518 0.300504 +0.472044 -0.840449 -0.266122 +0.016761 -0.961573 0.274037 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.482408 0.875946 +0.000000 -0.960502 0.278273 +0.016761 -0.961573 0.274037 +0.016761 -0.961573 0.274037 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.016761 -0.961573 0.274037 +0.000000 -0.999997 -0.002593 +0.000000 -0.999997 -0.002593 +0.000000 -0.482408 0.875946 +0.000000 -0.482408 0.875946 +0.016761 -0.961573 0.274037 +0.000000 -1.000000 0.000002 +0.204871 -0.931518 0.300504 +0.204871 -0.931518 0.300504 +0.278630 -0.944534 0.173843 +0.472044 -0.840449 -0.266122 +-0.000001 -0.480135 -0.877194 +0.000000 -0.999997 -0.002593 +0.016761 -0.961573 0.274037 +0.016761 -0.961573 0.274037 +0.472044 -0.840449 -0.266122 +-0.000001 -0.480135 -0.877194 +-0.159831 0.985228 -0.061474 +-0.159831 0.985228 -0.061474 +-0.705588 0.705377 -0.067746 +-0.705588 0.705377 -0.067746 +-0.705588 0.705376 -0.067746 +-0.159831 0.985228 -0.061474 +-0.987087 0.160182 0.000001 +-0.974743 0.158179 0.157659 +-0.700073 0.696893 0.155683 +-0.700073 0.696893 0.155683 +-0.707107 0.707107 0.000000 +-0.987087 0.160182 0.000001 +-0.705588 0.705377 -0.067746 +-0.985934 0.159934 -0.048521 +-0.985934 0.159934 -0.048521 +-0.985934 0.159934 -0.048521 +-0.705588 0.705376 -0.067746 +-0.705588 0.705377 -0.067746 +-0.707107 0.707107 0.000000 +-0.700073 0.696893 0.155683 +-0.155746 0.975487 0.155460 +-0.155746 0.975487 0.155460 +-0.160182 0.987087 0.000000 +-0.707107 0.707107 0.000000 +-0.155928 0.141040 0.977647 +-0.018551 0.170483 0.985186 +-0.107470 0.721820 0.683686 +-0.107470 0.721820 0.683686 +-0.541660 0.532699 0.650258 +-0.155928 0.141040 0.977647 +-0.173478 0.024209 0.984540 +-0.155928 0.141040 0.977647 +-0.541660 0.532699 0.650258 +-0.541660 0.532699 0.650258 +-0.720099 0.114166 0.684415 +-0.173478 0.024209 0.984540 +-0.541660 0.532699 0.650258 +-0.107470 0.721820 0.683686 +-0.155746 0.975487 0.155460 +-0.155746 0.975487 0.155460 +-0.700073 0.696893 0.155683 +-0.541660 0.532699 0.650258 +-0.720099 0.114166 0.684415 +-0.541660 0.532699 0.650258 +-0.700073 0.696893 0.155683 +-0.700073 0.696893 0.155683 +-0.974743 0.158179 0.157659 +-0.720099 0.114166 0.684415 +-0.902713 0.144766 -0.405157 +-0.645117 0.643053 -0.412683 +-0.456612 0.453865 -0.765188 +-0.456612 0.453865 -0.765188 +-0.676471 0.107125 -0.728637 +-0.902713 0.144766 -0.405157 +-0.456612 0.453865 -0.765188 +-0.645117 0.643053 -0.412683 +-0.144762 0.898824 -0.413714 +-0.144762 0.898824 -0.413714 +-0.107386 0.671902 -0.732814 +-0.456612 0.453865 -0.765188 +-0.676471 0.107125 -0.728637 +-0.692241 0.000000 -0.721666 +-0.911793 0.000000 -0.410650 +-0.911793 0.000000 -0.410650 +-0.902713 0.144766 -0.405157 +-0.676471 0.107125 -0.728637 +-0.911793 0.000000 -0.410650 +-0.911793 0.000000 -0.410650 +-0.692241 0.000000 -0.721666 +-0.692241 0.000000 -0.721666 +-0.692242 0.000000 -0.721666 +-0.911793 0.000000 -0.410650 +0.000000 -0.987088 -0.160182 +0.000000 -0.986432 -0.164170 +0.000000 -1.000000 0.000000 +0.000000 -0.987088 -0.160182 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.987088 -0.160182 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.986432 -0.164170 +0.000000 -0.987088 -0.160182 +0.000000 -0.707108 -0.707105 +0.000000 -0.707108 -0.707105 +0.000000 -0.701326 -0.712841 +0.000000 -0.986432 -0.164170 +0.000000 -0.701326 -0.712841 +0.000000 -0.707108 -0.707105 +0.000000 -0.160184 -0.987087 +0.000000 -0.160184 -0.987087 +0.000000 -0.159534 -0.987192 +0.000000 -0.701326 -0.712841 +0.000000 -0.159534 -0.987192 +0.000000 -0.160184 -0.987087 +-0.000000 0.160184 -0.987087 +-0.000000 0.160184 -0.987087 +-0.000000 0.159534 -0.987193 +0.000000 -0.159534 -0.987192 +-0.000000 0.160184 -0.987087 +-0.000000 0.707107 -0.707106 +-0.000000 0.701324 -0.712842 +-0.000000 0.701324 -0.712842 +-0.000000 0.159534 -0.987193 +-0.000000 0.160184 -0.987087 +-0.000000 0.707107 -0.707106 +-0.000000 0.987087 -0.160183 +-0.000000 0.986432 -0.164171 +-0.000000 0.986432 -0.164171 +-0.000000 0.701324 -0.712842 +-0.000000 0.707107 -0.707106 +0.000000 0.686823 -0.726825 +0.000000 0.906973 -0.421189 +0.000000 0.906973 -0.421189 +0.000000 0.906973 -0.421189 +0.000000 0.686823 -0.726825 +0.000000 0.686823 -0.726825 +0.000000 0.906973 -0.421189 +0.000000 0.686823 -0.726825 +-0.107386 0.671902 -0.732814 +-0.107386 0.671902 -0.732814 +-0.144762 0.898824 -0.413714 +0.000000 0.906973 -0.421189 +0.160183 0.000000 -0.987087 +0.707108 0.000000 -0.707105 +0.699024 0.000000 -0.715099 +0.699024 0.000000 -0.715099 +0.159277 0.000000 -0.987234 +0.160183 0.000000 -0.987087 +0.707108 0.000000 -0.707105 +0.987088 0.000000 -0.160182 +0.986171 0.000000 -0.165731 +0.986171 0.000000 -0.165731 +0.699024 0.000000 -0.715099 +0.707108 0.000000 -0.707105 +-0.987088 -0.000000 -0.160181 +-0.986171 -0.000000 -0.165730 +-1.000000 -0.000000 0.000000 +-0.987088 -0.000000 -0.160181 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.987088 -0.000000 -0.160181 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.986171 -0.000000 -0.165730 +-0.987088 -0.000000 -0.160181 +-0.707109 -0.000000 -0.707105 +-0.707109 -0.000000 -0.707105 +-0.699024 -0.000000 -0.715098 +-0.986171 -0.000000 -0.165730 +-0.699024 -0.000000 -0.715098 +-0.707109 -0.000000 -0.707105 +-0.160184 -0.000000 -0.987087 +-0.160184 -0.000000 -0.987087 +-0.159277 -0.000000 -0.987234 +-0.699024 -0.000000 -0.715098 +-0.159277 -0.000000 -0.987234 +-0.160184 -0.000000 -0.987087 +0.160183 0.000000 -0.987087 +0.160183 0.000000 -0.987087 +0.159277 0.000000 -0.987234 +-0.159277 -0.000000 -0.987234 +-0.987396 0.000000 0.158268 +-0.709858 0.000000 0.704345 +-0.720099 0.114166 0.684415 +-0.720099 0.114166 0.684415 +-0.974743 0.158179 0.157659 +-0.987396 0.000000 0.158268 +-0.709858 0.000000 0.704345 +-0.162115 0.000000 0.986772 +-0.173478 0.024209 0.984540 +-0.173478 0.024209 0.984540 +-0.720099 0.114166 0.684415 +-0.709858 0.000000 0.704345 +-0.162115 0.000000 0.986772 +-0.709857 0.000000 0.704345 +-0.709857 0.000000 0.704345 +-0.709857 0.000000 0.704345 +-0.162115 0.000000 0.986772 +-0.162115 0.000000 0.986772 +0.000000 0.707107 0.707106 +-0.000000 0.707109 0.707105 +-0.000000 0.987088 0.160181 +-0.000000 0.987088 0.160181 +0.000001 0.987087 0.160183 +0.000000 0.707107 0.707106 +-0.000000 0.160184 0.987087 +-0.000000 0.707109 0.707105 +0.000000 0.707107 0.707106 +0.000000 0.707107 0.707106 +-0.000000 0.160183 0.987087 +-0.000000 0.160184 0.987087 +0.000000 -0.160183 0.987087 +-0.000000 0.160184 0.987087 +-0.000000 0.160183 0.987087 +-0.000000 0.160183 0.987087 +0.000000 -0.160183 0.987087 +0.000000 -0.160183 0.987087 +0.000000 -0.707107 0.707106 +0.000000 -0.160183 0.987087 +0.000000 -0.160183 0.987087 +0.000000 -0.160183 0.987087 +0.000000 -0.707107 0.707106 +0.000000 -0.707107 0.707106 +0.000001 -0.987087 0.160183 +0.000000 -0.707107 0.707106 +0.000000 -0.707107 0.707106 +0.000000 -0.707107 0.707106 +0.000001 -0.987087 0.160183 +0.000001 -0.987087 0.160183 +0.000000 0.987396 0.158267 +0.000000 0.987396 0.158267 +0.000000 0.709859 0.704344 +0.000000 0.709859 0.704344 +0.000000 0.709859 0.704344 +0.000000 0.987396 0.158267 +0.000000 0.709859 0.704344 +0.000000 0.709859 0.704344 +0.000000 0.162115 0.986772 +0.000000 0.162115 0.986772 +0.000000 0.162115 0.986772 +0.000000 0.709859 0.704344 +0.000000 0.987396 0.158267 +-0.155746 0.975487 0.155460 +-0.107470 0.721820 0.683686 +-0.107470 0.721820 0.683686 +0.000000 0.709858 0.704344 +0.000000 0.987396 0.158267 +-0.018551 0.170483 0.985186 +0.000000 0.162115 0.986772 +0.000000 0.709858 0.704344 +0.000000 0.709858 0.704344 +-0.107470 0.721820 0.683686 +-0.018551 0.170483 0.985186 +0.160184 0.000000 0.987087 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +-0.160184 -0.000000 0.987087 +-0.160184 -0.000000 0.987087 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +-0.160184 -0.000000 0.987087 +-0.707108 -0.000001 0.707105 +-0.160184 -0.000000 0.987087 +-0.160184 -0.000000 0.987087 +-0.160184 -0.000000 0.987087 +-0.707108 0.000000 0.707106 +-0.707108 -0.000001 0.707105 +-0.987087 -0.000000 0.160183 +-0.987088 -0.000001 0.160181 +-0.707108 -0.000001 0.707105 +-0.707108 -0.000001 0.707105 +-0.707108 0.000000 0.707106 +-0.987087 -0.000000 0.160183 +0.707107 0.000000 0.707107 +0.987087 0.000000 0.160183 +0.987087 0.000000 0.160183 +0.987087 0.000000 0.160183 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.911793 0.000000 -0.410650 +-0.999196 0.000000 -0.040096 +-0.999195 0.000005 -0.040118 +-0.999195 0.000005 -0.040118 +-0.911793 0.000000 -0.410650 +-0.911793 0.000000 -0.410650 +-0.000000 1.000000 0.000000 +-0.000000 0.986432 -0.164171 +-0.000000 0.987087 -0.160183 +-0.000000 0.987087 -0.160183 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 0.987087 -0.160183 +-0.000000 1.000000 0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-0.000001 0.998442 -0.055795 +-0.000000 0.998442 -0.055795 +-0.000000 0.999610 -0.027909 +-0.000000 0.999610 -0.027909 +0.000000 0.999610 -0.027908 +-0.000001 0.998442 -0.055795 +1.000000 0.000000 0.000000 +0.986171 0.000000 -0.165731 +0.987088 0.000000 -0.160182 +0.987088 0.000000 -0.160182 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.987088 0.000000 -0.160182 +1.000000 0.000000 0.000000 +-0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-1.000000 0.000000 0.000001 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020064 +-0.999799 0.000000 -0.020064 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000001 +0.000001 0.987087 0.160183 +-0.000000 0.987088 0.160181 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000001 0.987087 0.160183 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +0.000001 -1.000000 -0.000000 +0.000001 -0.987087 0.160183 +0.000001 -0.987087 0.160183 +0.000001 -1.000000 -0.000000 +0.000001 -0.987087 0.160183 +0.000000 -1.000000 0.000000 +0.000001 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000001 +0.000001 -1.000000 -0.000000 +0.000000 -1.000000 0.000001 +0.000001 -1.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 -0.000000 +-0.162115 0.000000 0.986772 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.162115 0.000000 0.986772 +-0.162115 0.000000 0.986772 +-0.160182 0.987087 0.000000 +-0.155746 0.975487 0.155460 +0.000000 0.987396 0.158267 +0.000000 0.987396 0.158267 +0.000000 1.000000 0.000000 +-0.160182 0.987087 0.000000 +-0.987087 -0.000000 0.160183 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-0.987088 -0.000001 0.160181 +-0.987087 -0.000000 0.160183 +-1.000000 -0.000000 -0.000000 +-0.987088 -0.000001 0.160181 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.987087 0.000000 0.160183 +1.000000 0.000000 0.000000 +0.987087 0.000000 0.160183 +0.987087 0.000000 0.160183 +1.000000 0.000000 0.000000 +0.987087 0.000000 0.160183 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.987396 0.000000 0.158268 +-0.987396 0.000000 0.158268 +-0.709857 0.000000 0.704345 +-0.709857 0.000000 0.704345 +-0.709857 0.000000 0.704345 +-0.987396 0.000000 0.158268 +0.000000 0.000000 1.000000 +0.000000 0.162115 0.986772 +-0.018551 0.170483 0.985186 +0.000000 0.000000 1.000000 +-0.018551 0.170483 0.985186 +-0.173478 0.024209 0.984540 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.173478 0.024209 0.984540 +0.000000 0.000000 1.000000 +-0.173478 0.024209 0.984540 +-0.162115 0.000000 0.986772 +-0.173478 0.024209 0.984540 +-0.018551 0.170483 0.985186 +-0.155928 0.141040 0.977647 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.162115 0.986772 +0.000000 0.162115 0.986772 +0.000000 0.162115 0.986772 +0.000000 0.000000 1.000000 +-0.999195 -0.000000 -0.040117 +-0.999195 0.000000 -0.040117 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999195 -0.000000 -0.040117 +-0.999799 0.000000 -0.020062 +-1.000000 0.000000 0.000001 +-1.000000 -0.000000 0.000001 +-1.000000 -0.000000 0.000001 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999195 0.000000 -0.040116 +-0.999195 -0.000000 -0.040117 +-0.985934 0.159934 -0.048521 +-0.985934 0.159934 -0.048521 +-0.985934 0.159934 -0.048521 +-0.999195 0.000000 -0.040116 +-0.974743 0.158179 0.157659 +-0.987087 0.160182 0.000001 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987396 0.000000 0.158268 +-0.974743 0.158179 0.157659 +-1.000000 -0.000000 0.000001 +-1.000000 -0.000000 0.000001 +-0.999799 -0.000000 -0.020062 +-0.999799 -0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-1.000000 -0.000000 0.000001 +-0.999799 -0.000000 -0.020062 +-0.999195 -0.000000 -0.040117 +-0.999195 -0.000000 -0.040117 +-0.999195 -0.000000 -0.040117 +-0.999799 0.000000 -0.020062 +-0.999799 -0.000000 -0.020062 +-0.999195 0.000000 -0.040117 +-0.999195 0.000000 -0.040116 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-0.999195 0.000000 -0.040117 +-0.999799 0.000000 -0.020062 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-0.999799 0.000000 -0.020062 +-0.999799 0.000000 -0.020062 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000000 +-0.999195 0.000000 -0.040116 +-0.999195 0.000005 -0.040118 +-0.999196 0.000000 -0.040096 +-0.999196 0.000000 -0.040096 +-0.999196 0.000000 -0.040095 +-0.999195 0.000000 -0.040116 +-1.000000 -0.000000 0.000001 +-1.000000 0.000000 0.000000 +-0.987087 0.160182 0.000001 +-0.987087 0.160182 0.000001 +-0.987087 0.160182 0.000000 +-1.000000 -0.000000 0.000001 +-0.987087 0.160182 0.000000 +-0.987087 0.160182 0.000001 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.987087 0.160182 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.160182 0.987087 0.000000 +-0.160182 0.987087 0.000000 +-0.160182 0.987087 0.000000 +-0.707107 0.707107 0.000000 +-0.160182 0.987087 0.000000 +-0.160182 0.987087 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.160182 0.987087 0.000000 +-1.000000 -0.000000 0.000001 +-0.987087 0.160182 0.000000 +-0.986399 0.162556 -0.024328 +-0.986399 0.162556 -0.024328 +-0.999799 -0.000000 -0.020062 +-1.000000 -0.000000 0.000001 +-0.986399 0.162556 -0.024328 +-0.987087 0.160182 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.705633 0.707781 -0.033588 +-0.986399 0.162556 -0.024328 +-0.705633 0.707781 -0.033588 +-0.707107 0.707107 0.000000 +-0.160182 0.987087 0.000000 +-0.160182 0.987087 0.000000 +-0.161626 0.986374 -0.030703 +-0.705633 0.707781 -0.033588 +0.000000 0.999610 -0.027908 +-0.000000 0.999610 -0.027909 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999610 -0.027908 +-0.000001 0.998442 -0.055795 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000001 0.998442 -0.055795 +-0.000001 0.998442 -0.055795 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999610 -0.027908 +-0.161626 0.986374 -0.030703 +-0.160182 0.987087 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.999610 -0.027909 +-0.161626 0.986374 -0.030703 +-0.159831 0.985228 -0.061474 +-0.000000 0.998442 -0.055795 +-0.000000 0.998442 -0.055794 +-0.000000 0.998442 -0.055794 +-0.159831 0.985228 -0.061474 +-0.159831 0.985228 -0.061474 +-0.000000 0.999610 -0.027909 +-0.000000 0.998442 -0.055795 +-0.159831 0.985228 -0.061474 +-0.159831 0.985228 -0.061474 +-0.161626 0.986374 -0.030703 +-0.000000 0.999610 -0.027909 +-0.161626 0.986374 -0.030703 +-0.159831 0.985228 -0.061474 +-0.705588 0.705376 -0.067746 +-0.705588 0.705376 -0.067746 +-0.705633 0.707781 -0.033588 +-0.161626 0.986374 -0.030703 +-0.705588 0.705376 -0.067746 +-0.985934 0.159934 -0.048521 +-0.986399 0.162556 -0.024328 +-0.986399 0.162556 -0.024328 +-0.705633 0.707781 -0.033588 +-0.705588 0.705376 -0.067746 +-0.999195 -0.000000 -0.040117 +-0.999799 -0.000000 -0.020062 +-0.986399 0.162556 -0.024328 +-0.986399 0.162556 -0.024328 +-0.985934 0.159934 -0.048521 +-0.999195 -0.000000 -0.040117 +-0.999195 0.000000 -0.040116 +-0.985934 0.159934 -0.048521 +-0.902713 0.144766 -0.405157 +-0.902713 0.144766 -0.405157 +-0.911793 0.000000 -0.410650 +-0.999195 0.000000 -0.040116 +-0.985934 0.159934 -0.048521 +-0.705588 0.705377 -0.067746 +-0.645117 0.643053 -0.412683 +-0.645117 0.643053 -0.412683 +-0.902713 0.144766 -0.405157 +-0.985934 0.159934 -0.048521 +-0.645117 0.643053 -0.412683 +-0.705588 0.705377 -0.067746 +-0.159831 0.985228 -0.061474 +-0.159831 0.985228 -0.061474 +-0.144762 0.898824 -0.413714 +-0.645117 0.643053 -0.412683 +-0.144762 0.898824 -0.413714 +-0.159831 0.985228 -0.061474 +-0.000000 0.998442 -0.055794 +-0.000000 0.998442 -0.055794 +0.000000 0.906973 -0.421189 +-0.144762 0.898824 -0.413714 +-0.000000 0.998441 -0.055810 +-0.000005 0.998442 -0.055795 +-0.000001 0.999610 -0.027908 +-0.000001 0.999610 -0.027908 +0.000000 0.999611 -0.027905 +-0.000000 0.998441 -0.055810 +0.000000 0.987396 0.158267 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.987396 0.158267 +0.000000 0.987396 0.158267 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000001 0.999610 -0.027908 +-0.000001 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000000 1.000000 0.000000 +-0.000001 0.999610 -0.027908 +-0.000005 0.998442 -0.055795 +0.000001 0.998442 -0.055795 +0.000001 0.998442 -0.055795 +0.000000 0.999610 -0.027908 +-0.000001 0.999610 -0.027908 +-0.000002 0.998442 -0.055798 +-0.000005 0.998442 -0.055795 +-0.000000 0.998441 -0.055810 +-0.000000 0.998441 -0.055810 +-0.000000 0.998441 -0.055815 +-0.000002 0.998442 -0.055798 +-0.000002 0.998442 -0.055798 +-0.000000 0.998441 -0.055815 +0.000000 0.906973 -0.421189 +0.000000 0.906973 -0.421189 +0.000000 0.906973 -0.421189 +-0.000002 0.998442 -0.055798 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999611 -0.027905 +0.000000 0.999611 -0.027905 +-0.000001 0.999610 -0.027908 +0.000000 1.000000 0.000000 +-0.987396 0.000000 0.158268 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-0.987396 0.000000 0.158268 +-0.987396 0.000000 0.158268 +-0.999195 0.000000 -0.040116 +-0.999196 0.000000 -0.040095 +-0.999799 0.000000 -0.020064 +-0.999799 0.000000 -0.020064 +-0.999799 0.000000 -0.020062 +-0.999195 0.000000 -0.040116 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000001 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000001 +-1.000000 -0.000000 -0.000001 +-1.000000 -0.000000 -0.000001 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000001 +-1.000000 -0.000000 -0.000001 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000001 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000001 +-0.000000 1.000000 -0.000001 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000003 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000003 +0.000000 1.000000 0.000003 +-0.000000 1.000000 0.000021 +0.000000 1.000000 0.000001 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.293668 0.950362 -0.102818 +0.437377 0.898427 0.039117 +0.466777 0.877351 -0.111237 +0.466777 0.877351 -0.111237 +-0.378489 0.922436 0.076533 +-0.293668 0.950362 -0.102818 +-0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +-0.053947 0.933079 -0.355602 +-0.053947 0.933079 -0.355602 +0.000000 0.928568 -0.371161 +-0.000000 1.000000 0.000002 +0.083860 0.883048 -0.461729 +-0.058021 0.917041 0.394549 +-0.219047 0.944662 0.244197 +-0.219047 0.944662 0.244197 +0.334821 0.862576 -0.379285 +0.083860 0.883048 -0.461729 +0.278630 0.944534 0.173843 +-0.199706 0.956891 -0.210898 +-0.126855 0.942566 -0.308993 +-0.126855 0.942566 -0.308993 +0.204871 0.931518 0.300504 +0.278630 0.944534 0.173843 +0.437377 0.898427 0.039117 +-0.293668 0.950362 -0.102818 +-0.199706 0.956891 -0.210898 +-0.199706 0.956891 -0.210898 +0.278630 0.944534 0.173843 +0.437377 0.898427 0.039117 +0.000000 0.902777 -0.430109 +0.000000 0.903393 0.428813 +-0.058021 0.917041 0.394549 +-0.058021 0.917041 0.394549 +0.083860 0.883048 -0.461729 +0.000000 0.902777 -0.430109 +-0.219047 0.944662 0.244197 +-0.378489 0.922436 0.076533 +0.466777 0.877351 -0.111237 +0.466777 0.877351 -0.111237 +0.334821 0.862576 -0.379285 +-0.219047 0.944662 0.244197 +0.204871 0.931518 0.300504 +-0.126855 0.942566 -0.308993 +-0.053947 0.933079 -0.355602 +-0.053947 0.933079 -0.355602 +0.000000 1.000000 0.000002 +0.204871 0.931518 0.300504 +-0.984855 0.000001 0.173381 +-0.973923 0.000000 -0.226877 +-0.906193 0.386266 -0.172083 +-0.906193 0.386266 -0.172083 +-0.924386 0.345298 0.162109 +-0.984855 0.000001 0.173381 +0.965948 0.000000 0.258737 +0.972507 0.000000 -0.232875 +0.922754 0.317517 -0.218422 +0.922754 0.317517 -0.218422 +0.876796 0.404449 0.260095 +0.965948 0.000000 0.258737 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.000000 1.000000 +-0.165253 0.000000 -0.986251 +0.000000 0.000000 -1.000000 +0.000000 0.389580 -0.920992 +0.000000 0.389580 -0.920992 +-0.145080 0.399992 -0.904963 +-0.165253 0.000000 -0.986251 +0.661497 0.000000 -0.749948 +0.174458 0.000000 -0.984665 +0.161326 0.320071 -0.933557 +0.161326 0.320071 -0.933557 +0.628452 0.312262 -0.712418 +0.661497 0.000000 -0.749948 +-0.139943 0.000000 0.990160 +-0.682762 0.000000 0.730641 +-0.629331 0.383170 0.676109 +-0.629331 0.383170 0.676109 +-0.134000 0.341445 0.930301 +-0.139943 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.865983 0.000000 -0.500074 +0.472043 0.840449 -0.266122 +0.472043 0.840449 -0.266122 +-0.000001 0.480135 -0.877194 +0.000000 0.000000 -1.000000 +-0.973923 0.000000 -0.226877 +-0.766123 0.000000 -0.642694 +-0.686198 0.460064 -0.563448 +-0.686198 0.460064 -0.563448 +-0.906193 0.386266 -0.172083 +-0.973923 0.000000 -0.226877 +0.865983 0.000000 -0.500074 +0.965948 0.000000 0.258737 +0.876796 0.404449 0.260095 +0.876796 0.404449 0.260095 +0.472043 0.840449 -0.266122 +0.865983 0.000000 -0.500074 +0.000000 0.000000 1.000000 +-0.139943 0.000000 0.990160 +-0.134000 0.341445 0.930301 +-0.134000 0.341445 0.930301 +0.000000 0.335574 0.942014 +0.000000 0.000000 1.000000 +0.174458 0.000000 -0.984665 +0.000000 0.000000 -1.000000 +-0.000000 0.335181 -0.942154 +-0.000000 0.335181 -0.942154 +0.161326 0.320071 -0.933557 +0.174458 0.000000 -0.984665 +0.972507 0.000000 -0.232875 +0.661497 0.000000 -0.749948 +0.628452 0.312262 -0.712418 +0.628452 0.312262 -0.712418 +0.922754 0.317517 -0.218422 +0.972507 0.000000 -0.232875 +-0.682762 0.000000 0.730641 +-0.984855 0.000001 0.173381 +-0.924386 0.345298 0.162109 +-0.924386 0.345298 0.162109 +-0.629331 0.383170 0.676109 +-0.682762 0.000000 0.730641 +-0.446771 0.000000 -0.894648 +-0.165253 0.000000 -0.986251 +-0.145080 0.399992 -0.904963 +-0.145080 0.399992 -0.904963 +-0.391985 0.437360 -0.809360 +-0.446771 0.000000 -0.894648 +-0.766123 0.000000 -0.642694 +-0.446771 0.000000 -0.894648 +-0.391985 0.437360 -0.809360 +-0.391985 0.437360 -0.809360 +-0.686198 0.460064 -0.563448 +-0.766123 0.000000 -0.642694 +0.437377 0.898427 0.039117 +0.876796 0.404449 0.260095 +0.922754 0.317517 -0.218422 +0.922754 0.317517 -0.218422 +0.466777 0.877351 -0.111237 +0.437377 0.898427 0.039117 +-0.378489 0.922436 0.076533 +-0.924386 0.345298 0.162109 +-0.906193 0.386266 -0.172083 +-0.906193 0.386266 -0.172083 +-0.293668 0.950362 -0.102818 +-0.378489 0.922436 0.076533 +0.000000 0.960502 0.278273 +0.016761 0.961573 0.274037 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +-0.000000 1.000000 0.000002 +0.000000 0.960502 0.278273 +-0.145080 0.399992 -0.904963 +0.000000 0.389580 -0.920992 +0.000000 0.928568 -0.371161 +0.000000 0.928568 -0.371161 +-0.053947 0.933079 -0.355602 +-0.145080 0.399992 -0.904963 +-0.058021 0.917041 0.394549 +-0.134000 0.341445 0.930301 +-0.629331 0.383170 0.676109 +-0.629331 0.383170 0.676109 +-0.219047 0.944662 0.244197 +-0.058021 0.917041 0.394549 +0.334821 0.862576 -0.379285 +0.628452 0.312262 -0.712418 +0.161326 0.320071 -0.933557 +0.161326 0.320071 -0.933557 +0.083860 0.883048 -0.461729 +0.334821 0.862576 -0.379285 +-0.199706 0.956891 -0.210898 +-0.686198 0.460064 -0.563448 +-0.391985 0.437360 -0.809360 +-0.391985 0.437360 -0.809360 +-0.126855 0.942566 -0.308993 +-0.199706 0.956891 -0.210898 +-0.293668 0.950362 -0.102818 +-0.906193 0.386266 -0.172083 +-0.686198 0.460064 -0.563448 +-0.686198 0.460064 -0.563448 +-0.199706 0.956891 -0.210898 +-0.293668 0.950362 -0.102818 +0.278630 0.944534 0.173843 +0.472043 0.840449 -0.266122 +0.876796 0.404449 0.260095 +0.876796 0.404449 0.260095 +0.437377 0.898427 0.039117 +0.278630 0.944534 0.173843 +0.000000 0.903393 0.428813 +0.000000 0.335574 0.942014 +-0.134000 0.341445 0.930301 +-0.134000 0.341445 0.930301 +-0.058021 0.917041 0.394549 +0.000000 0.903393 0.428813 +0.161326 0.320071 -0.933557 +-0.000000 0.335181 -0.942154 +0.000000 0.902777 -0.430109 +0.000000 0.902777 -0.430109 +0.083860 0.883048 -0.461729 +0.161326 0.320071 -0.933557 +-0.629331 0.383170 0.676109 +-0.924386 0.345298 0.162109 +-0.378489 0.922436 0.076533 +-0.378489 0.922436 0.076533 +-0.219047 0.944662 0.244197 +-0.629331 0.383170 0.676109 +0.922754 0.317517 -0.218422 +0.628452 0.312262 -0.712418 +0.334821 0.862576 -0.379285 +0.334821 0.862576 -0.379285 +0.466777 0.877351 -0.111237 +0.922754 0.317517 -0.218422 +-0.126855 0.942566 -0.308993 +-0.391985 0.437360 -0.809360 +-0.145080 0.399992 -0.904963 +-0.145080 0.399992 -0.904963 +-0.053947 0.933079 -0.355602 +-0.126855 0.942566 -0.308993 +0.204871 0.931518 0.300504 +0.016761 0.961573 0.274037 +0.472043 0.840449 -0.266122 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.016761 0.961573 0.274037 +0.016761 0.961573 0.274037 +0.000000 0.960502 0.278273 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.999997 -0.002593 +0.000000 0.999997 -0.002593 +0.016761 0.961573 0.274037 +0.000000 0.482408 0.875946 +0.016761 0.961573 0.274037 +0.204871 0.931518 0.300504 +0.000000 1.000000 0.000002 +0.204871 0.931518 0.300504 +0.472043 0.840449 -0.266122 +0.278630 0.944534 0.173843 +-0.000001 0.480135 -0.877194 +0.472043 0.840449 -0.266122 +0.016761 0.961573 0.274037 +0.016761 0.961573 0.274037 +0.000000 0.999997 -0.002593 +-0.000001 0.480135 -0.877194 +0.293668 0.950362 -0.102818 +0.378489 0.922436 0.076533 +-0.466777 0.877352 -0.111236 +-0.466777 0.877352 -0.111236 +-0.437377 0.898427 0.039117 +0.293668 0.950362 -0.102818 +-0.000000 1.000000 0.000002 +0.000000 0.928568 -0.371161 +0.053947 0.933079 -0.355603 +0.053947 0.933079 -0.355603 +0.000000 1.000000 0.000002 +-0.000000 1.000000 0.000002 +-0.083860 0.883048 -0.461729 +-0.334821 0.862576 -0.379285 +0.219047 0.944662 0.244196 +0.219047 0.944662 0.244196 +0.058021 0.917041 0.394549 +-0.083860 0.883048 -0.461729 +-0.278630 0.944534 0.173843 +-0.204871 0.931518 0.300504 +0.126855 0.942566 -0.308993 +0.126855 0.942566 -0.308993 +0.199706 0.956891 -0.210898 +-0.278630 0.944534 0.173843 +-0.437377 0.898427 0.039117 +-0.278630 0.944534 0.173843 +0.199706 0.956891 -0.210898 +0.199706 0.956891 -0.210898 +0.293668 0.950362 -0.102818 +-0.437377 0.898427 0.039117 +0.000000 0.902777 -0.430109 +-0.083860 0.883048 -0.461729 +0.058021 0.917041 0.394549 +0.058021 0.917041 0.394549 +0.000000 0.903393 0.428813 +0.000000 0.902777 -0.430109 +0.219047 0.944662 0.244196 +-0.334821 0.862576 -0.379285 +-0.466777 0.877352 -0.111236 +-0.466777 0.877352 -0.111236 +0.378489 0.922436 0.076533 +0.219047 0.944662 0.244196 +-0.204871 0.931518 0.300504 +0.000000 1.000000 0.000002 +0.053947 0.933079 -0.355603 +0.053947 0.933079 -0.355603 +0.126855 0.942566 -0.308993 +-0.204871 0.931518 0.300504 +0.984855 0.000001 0.173382 +0.924386 0.345297 0.162111 +0.906193 0.386266 -0.172082 +0.906193 0.386266 -0.172082 +0.973923 0.000000 -0.226877 +0.984855 0.000001 0.173382 +-0.965948 0.000000 0.258737 +-0.876796 0.404449 0.260094 +-0.922754 0.317518 -0.218422 +-0.922754 0.317518 -0.218422 +-0.972507 0.000000 -0.232875 +-0.965948 0.000000 0.258737 +0.000000 0.000000 1.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.165253 0.000000 -0.986251 +0.145080 0.399992 -0.904963 +0.000000 0.389580 -0.920992 +0.000000 0.389580 -0.920992 +0.000000 0.000000 -1.000000 +0.165253 0.000000 -0.986251 +-0.661497 0.000000 -0.749948 +-0.628452 0.312262 -0.712418 +-0.161326 0.320071 -0.933557 +-0.161326 0.320071 -0.933557 +-0.174458 0.000000 -0.984665 +-0.661497 0.000000 -0.749948 +0.139943 0.000000 0.990160 +0.134000 0.341445 0.930301 +0.629330 0.383170 0.676110 +0.629330 0.383170 0.676110 +0.682761 0.000001 0.730642 +0.139943 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000001 0.480135 -0.877194 +-0.472044 0.840449 -0.266122 +-0.472044 0.840449 -0.266122 +-0.865983 0.000000 -0.500074 +0.000000 0.000000 -1.000000 +0.973923 0.000000 -0.226877 +0.906193 0.386266 -0.172082 +0.686198 0.460063 -0.563448 +0.686198 0.460063 -0.563448 +0.766123 0.000000 -0.642694 +0.973923 0.000000 -0.226877 +-0.865983 0.000000 -0.500074 +-0.472044 0.840449 -0.266122 +-0.876796 0.404449 0.260094 +-0.876796 0.404449 0.260094 +-0.965948 0.000000 0.258737 +-0.865983 0.000000 -0.500074 +0.000000 0.000000 1.000000 +0.000000 0.335574 0.942014 +0.134000 0.341445 0.930301 +0.134000 0.341445 0.930301 +0.139943 0.000000 0.990160 +0.000000 0.000000 1.000000 +-0.174458 0.000000 -0.984665 +-0.161326 0.320071 -0.933557 +-0.000000 0.335181 -0.942154 +-0.000000 0.335181 -0.942154 +0.000000 0.000000 -1.000000 +-0.174458 0.000000 -0.984665 +-0.972507 0.000000 -0.232875 +-0.922754 0.317518 -0.218422 +-0.628452 0.312262 -0.712418 +-0.628452 0.312262 -0.712418 +-0.661497 0.000000 -0.749948 +-0.972507 0.000000 -0.232875 +0.682761 0.000001 0.730642 +0.629330 0.383170 0.676110 +0.924386 0.345297 0.162111 +0.924386 0.345297 0.162111 +0.984855 0.000001 0.173382 +0.682761 0.000001 0.730642 +0.446771 0.000000 -0.894648 +0.391985 0.437360 -0.809360 +0.145080 0.399992 -0.904963 +0.145080 0.399992 -0.904963 +0.165253 0.000000 -0.986251 +0.446771 0.000000 -0.894648 +0.766123 0.000000 -0.642694 +0.686198 0.460063 -0.563448 +0.391985 0.437360 -0.809360 +0.391985 0.437360 -0.809360 +0.446771 0.000000 -0.894648 +0.766123 0.000000 -0.642694 +-0.437377 0.898427 0.039117 +-0.466777 0.877352 -0.111236 +-0.922754 0.317518 -0.218422 +-0.922754 0.317518 -0.218422 +-0.876796 0.404449 0.260094 +-0.437377 0.898427 0.039117 +0.378489 0.922436 0.076533 +0.293668 0.950362 -0.102818 +0.906193 0.386266 -0.172082 +0.906193 0.386266 -0.172082 +0.924386 0.345297 0.162111 +0.378489 0.922436 0.076533 +0.000000 0.960502 0.278273 +-0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +-0.016761 0.961573 0.274037 +0.000000 0.960502 0.278273 +0.145080 0.399992 -0.904963 +0.053947 0.933079 -0.355603 +0.000000 0.928568 -0.371161 +0.000000 0.928568 -0.371161 +0.000000 0.389580 -0.920992 +0.145080 0.399992 -0.904963 +0.058021 0.917041 0.394549 +0.219047 0.944662 0.244196 +0.629330 0.383170 0.676110 +0.629330 0.383170 0.676110 +0.134000 0.341445 0.930301 +0.058021 0.917041 0.394549 +-0.334821 0.862576 -0.379285 +-0.083860 0.883048 -0.461729 +-0.161326 0.320071 -0.933557 +-0.161326 0.320071 -0.933557 +-0.628452 0.312262 -0.712418 +-0.334821 0.862576 -0.379285 +0.199706 0.956891 -0.210898 +0.126855 0.942566 -0.308993 +0.391985 0.437360 -0.809360 +0.391985 0.437360 -0.809360 +0.686198 0.460063 -0.563448 +0.199706 0.956891 -0.210898 +0.293668 0.950362 -0.102818 +0.199706 0.956891 -0.210898 +0.686198 0.460063 -0.563448 +0.686198 0.460063 -0.563448 +0.906193 0.386266 -0.172082 +0.293668 0.950362 -0.102818 +-0.278630 0.944534 0.173843 +-0.437377 0.898427 0.039117 +-0.876796 0.404449 0.260094 +-0.876796 0.404449 0.260094 +-0.472044 0.840449 -0.266122 +-0.278630 0.944534 0.173843 +0.000000 0.903393 0.428813 +0.058021 0.917041 0.394549 +0.134000 0.341445 0.930301 +0.134000 0.341445 0.930301 +0.000000 0.335574 0.942014 +0.000000 0.903393 0.428813 +-0.161326 0.320071 -0.933557 +-0.083860 0.883048 -0.461729 +0.000000 0.902777 -0.430109 +0.000000 0.902777 -0.430109 +-0.000000 0.335181 -0.942154 +-0.161326 0.320071 -0.933557 +0.629330 0.383170 0.676110 +0.219047 0.944662 0.244196 +0.378489 0.922436 0.076533 +0.378489 0.922436 0.076533 +0.924386 0.345297 0.162111 +0.629330 0.383170 0.676110 +-0.922754 0.317518 -0.218422 +-0.466777 0.877352 -0.111236 +-0.334821 0.862576 -0.379285 +-0.334821 0.862576 -0.379285 +-0.628452 0.312262 -0.712418 +-0.922754 0.317518 -0.218422 +0.126855 0.942566 -0.308993 +0.053947 0.933079 -0.355603 +0.145080 0.399992 -0.904963 +0.145080 0.399992 -0.904963 +0.391985 0.437360 -0.809360 +0.126855 0.942566 -0.308993 +-0.204871 0.931518 0.300504 +-0.472044 0.840449 -0.266122 +-0.016761 0.961573 0.274037 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.482408 0.875946 +0.000000 0.960502 0.278273 +-0.016761 0.961573 0.274037 +-0.016761 0.961573 0.274037 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +-0.016761 0.961573 0.274037 +0.000000 0.999997 -0.002593 +0.000000 0.999997 -0.002593 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +-0.016761 0.961573 0.274037 +0.000000 1.000000 0.000002 +-0.204871 0.931518 0.300504 +-0.204871 0.931518 0.300504 +-0.278630 0.944534 0.173843 +-0.472044 0.840449 -0.266122 +0.000001 0.480135 -0.877194 +0.000000 0.999997 -0.002593 +-0.016761 0.961573 0.274037 +-0.016761 0.961573 0.274037 +-0.472044 0.840449 -0.266122 +0.000001 0.480135 -0.877194 +0.159831 0.985228 -0.061474 +0.705588 0.705376 -0.067746 +0.705588 0.705377 -0.067746 +0.705588 0.705377 -0.067746 +0.159831 0.985228 -0.061474 +0.159831 0.985228 -0.061474 +0.987087 0.160182 0.000001 +0.707107 0.707107 0.000000 +0.700074 0.696893 0.155682 +0.700074 0.696893 0.155682 +0.974743 0.158179 0.157659 +0.987087 0.160182 0.000001 +0.705588 0.705377 -0.067746 +0.705588 0.705376 -0.067746 +0.985934 0.159933 -0.048522 +0.985934 0.159933 -0.048522 +0.985935 0.159933 -0.048523 +0.705588 0.705377 -0.067746 +0.707107 0.707107 0.000000 +0.160182 0.987087 0.000000 +0.155746 0.975487 0.155460 +0.155746 0.975487 0.155460 +0.700074 0.696893 0.155682 +0.707107 0.707107 0.000000 +0.155927 0.141040 0.977647 +0.541661 0.532698 0.650258 +0.107470 0.721820 0.683686 +0.107470 0.721820 0.683686 +0.018551 0.170483 0.985186 +0.155927 0.141040 0.977647 +0.173478 0.024209 0.984540 +0.720099 0.114166 0.684415 +0.541661 0.532698 0.650258 +0.541661 0.532698 0.650258 +0.155927 0.141040 0.977647 +0.173478 0.024209 0.984540 +0.541661 0.532698 0.650258 +0.700074 0.696893 0.155682 +0.155746 0.975487 0.155460 +0.155746 0.975487 0.155460 +0.107470 0.721820 0.683686 +0.541661 0.532698 0.650258 +0.720099 0.114166 0.684415 +0.974743 0.158179 0.157659 +0.700074 0.696893 0.155682 +0.700074 0.696893 0.155682 +0.541661 0.532698 0.650258 +0.720099 0.114166 0.684415 +0.902713 0.144766 -0.405157 +0.676471 0.107126 -0.728637 +0.456612 0.453865 -0.765188 +0.456612 0.453865 -0.765188 +0.645117 0.643053 -0.412683 +0.902713 0.144766 -0.405157 +0.456612 0.453865 -0.765188 +0.107386 0.671902 -0.732814 +0.144762 0.898824 -0.413714 +0.144762 0.898824 -0.413714 +0.645117 0.643053 -0.412683 +0.456612 0.453865 -0.765188 +0.676471 0.107126 -0.728637 +0.902713 0.144766 -0.405157 +0.911793 0.000000 -0.410650 +0.911793 0.000000 -0.410650 +0.692241 0.000000 -0.721666 +0.676471 0.107126 -0.728637 +0.911793 0.000000 -0.410650 +0.692242 0.000000 -0.721666 +0.692241 0.000000 -0.721666 +0.692241 0.000000 -0.721666 +0.911793 0.000000 -0.410650 +0.911793 0.000000 -0.410650 +0.000000 -0.987087 -0.160182 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.987087 -0.160182 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.987087 -0.160182 +0.000000 -1.000000 0.000000 +0.000000 -0.986432 -0.164170 +0.000000 -0.986432 -0.164170 +0.000000 -0.701325 -0.712842 +0.000000 -0.707108 -0.707105 +0.000000 -0.707108 -0.707105 +0.000000 -0.987087 -0.160182 +0.000000 -0.986432 -0.164170 +0.000000 -0.701325 -0.712842 +0.000000 -0.159534 -0.987193 +0.000000 -0.160184 -0.987087 +0.000000 -0.160184 -0.987087 +0.000000 -0.707108 -0.707105 +0.000000 -0.701325 -0.712842 +0.000000 -0.159534 -0.987193 +0.000000 0.159534 -0.987192 +0.000000 0.160184 -0.987087 +0.000000 0.160184 -0.987087 +0.000000 -0.160184 -0.987087 +0.000000 -0.159534 -0.987193 +0.000000 0.160184 -0.987087 +0.000000 0.159534 -0.987192 +0.000000 0.701324 -0.712843 +0.000000 0.701324 -0.712843 +0.000000 0.707107 -0.707106 +0.000000 0.160184 -0.987087 +0.000000 0.707107 -0.707106 +0.000000 0.701324 -0.712843 +0.000000 0.986432 -0.164171 +0.000000 0.986432 -0.164171 +0.000000 0.987087 -0.160183 +0.000000 0.707107 -0.707106 +0.000000 0.686823 -0.726825 +0.000000 0.686823 -0.726825 +0.000000 0.906973 -0.421189 +0.000000 0.906973 -0.421189 +0.000000 0.906973 -0.421189 +0.000000 0.686823 -0.726825 +0.000000 0.906973 -0.421189 +0.144762 0.898824 -0.413714 +0.107386 0.671902 -0.732814 +0.107386 0.671902 -0.732814 +0.000000 0.686823 -0.726825 +0.000000 0.906973 -0.421189 +-0.160183 0.000000 -0.987087 +-0.159277 0.000000 -0.987234 +-0.699024 0.000000 -0.715098 +-0.699024 0.000000 -0.715098 +-0.707108 0.000000 -0.707105 +-0.160183 0.000000 -0.987087 +-0.707108 0.000000 -0.707105 +-0.699024 0.000000 -0.715098 +-0.986171 0.000000 -0.165730 +-0.986171 0.000000 -0.165730 +-0.987088 0.000000 -0.160181 +-0.707108 0.000000 -0.707105 +0.987088 -0.000000 -0.160181 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.987088 -0.000000 -0.160181 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.987088 -0.000000 -0.160181 +1.000000 -0.000000 0.000000 +0.986171 -0.000000 -0.165731 +0.986171 -0.000000 -0.165731 +0.699024 -0.000000 -0.715098 +0.707109 -0.000000 -0.707105 +0.707109 -0.000000 -0.707105 +0.987088 -0.000000 -0.160181 +0.986171 -0.000000 -0.165731 +0.699024 -0.000000 -0.715098 +0.159277 -0.000000 -0.987234 +0.160184 -0.000000 -0.987087 +0.160184 -0.000000 -0.987087 +0.707109 -0.000000 -0.707105 +0.699024 -0.000000 -0.715098 +0.159277 -0.000000 -0.987234 +-0.159277 0.000000 -0.987234 +-0.160183 0.000000 -0.987087 +-0.160183 0.000000 -0.987087 +0.160184 -0.000000 -0.987087 +0.159277 -0.000000 -0.987234 +0.987396 0.000000 0.158268 +0.974743 0.158179 0.157659 +0.720099 0.114166 0.684415 +0.720099 0.114166 0.684415 +0.709858 0.000000 0.704345 +0.987396 0.000000 0.158268 +0.709858 0.000000 0.704345 +0.720099 0.114166 0.684415 +0.173478 0.024209 0.984540 +0.173478 0.024209 0.984540 +0.162115 0.000000 0.986772 +0.709858 0.000000 0.704345 +0.162115 -0.000000 0.986772 +0.162115 0.000000 0.986772 +0.709857 0.000000 0.704345 +0.709857 0.000000 0.704345 +0.709858 0.000000 0.704345 +0.162115 -0.000000 0.986772 +-0.000000 0.707107 0.707106 +-0.000001 0.987087 0.160183 +0.000000 0.987088 0.160181 +0.000000 0.987088 0.160181 +0.000000 0.707109 0.707105 +-0.000000 0.707107 0.707106 +0.000000 0.160184 0.987087 +0.000000 0.160183 0.987087 +-0.000000 0.707107 0.707106 +-0.000000 0.707107 0.707106 +0.000000 0.707109 0.707105 +0.000000 0.160184 0.987087 +-0.000000 -0.160183 0.987087 +-0.000000 -0.160183 0.987087 +0.000000 0.160183 0.987087 +0.000000 0.160183 0.987087 +0.000000 0.160184 0.987087 +-0.000000 -0.160183 0.987087 +-0.000000 -0.707107 0.707106 +-0.000000 -0.707107 0.707106 +-0.000000 -0.160183 0.987087 +-0.000000 -0.160183 0.987087 +-0.000000 -0.160183 0.987087 +-0.000000 -0.707107 0.707106 +-0.000001 -0.987087 0.160183 +-0.000001 -0.987087 0.160183 +-0.000000 -0.707107 0.707106 +-0.000000 -0.707107 0.707106 +-0.000000 -0.707107 0.707106 +-0.000001 -0.987087 0.160183 +0.000000 0.987396 0.158267 +0.000000 0.709859 0.704344 +0.000000 0.709859 0.704344 +0.000000 0.709859 0.704344 +0.000000 0.987396 0.158267 +0.000000 0.987396 0.158267 +0.000000 0.709859 0.704344 +0.000000 0.162115 0.986772 +0.000000 0.162115 0.986772 +0.000000 0.162115 0.986772 +0.000000 0.709859 0.704344 +0.000000 0.709859 0.704344 +0.000000 0.987396 0.158267 +0.000000 0.709858 0.704344 +0.107470 0.721820 0.683686 +0.107470 0.721820 0.683686 +0.155746 0.975487 0.155460 +0.000000 0.987396 0.158267 +0.018551 0.170483 0.985186 +0.107470 0.721820 0.683686 +0.000000 0.709858 0.704344 +0.000000 0.709858 0.704344 +0.000000 0.162115 0.986772 +0.018551 0.170483 0.985186 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.707107 0.000000 0.707106 +-0.707107 0.000000 0.707106 +-0.707107 0.000000 0.707106 +-0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +-0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.707108 -0.000001 0.707105 +0.707108 0.000000 0.707106 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.160184 0.000000 0.987087 +0.707108 -0.000001 0.707105 +0.987087 -0.000000 0.160183 +0.707108 0.000000 0.707106 +0.707108 -0.000001 0.707105 +0.707108 -0.000001 0.707105 +0.987088 -0.000001 0.160180 +0.987087 -0.000000 0.160183 +-0.707107 0.000000 0.707106 +-0.707107 0.000000 0.707106 +-0.987087 0.000000 0.160183 +-0.987087 0.000000 0.160183 +-0.987087 0.000000 0.160183 +-0.707107 0.000000 0.707106 +0.911793 0.000000 -0.410650 +0.911793 0.000000 -0.410650 +0.999195 0.000005 -0.040120 +0.999195 0.000005 -0.040120 +0.999196 -0.000000 -0.040096 +0.911793 0.000000 -0.410650 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.987087 -0.160183 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.987087 -0.160183 +0.000000 1.000000 0.000000 +0.000000 0.987087 -0.160183 +0.000000 0.986432 -0.164171 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +0.000001 0.998442 -0.055795 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000000 0.998442 -0.055795 +0.000001 0.998442 -0.055795 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987088 0.000000 -0.160181 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987088 0.000000 -0.160181 +-1.000000 0.000000 0.000000 +-0.987088 0.000000 -0.160181 +-0.986171 0.000000 -0.165730 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000000 +0.999799 0.000000 -0.020063 +0.999799 0.000000 -0.020063 +0.999799 0.000000 -0.020062 +1.000000 0.000000 0.000001 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +-0.000001 0.987087 0.160183 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +-0.000001 0.987087 0.160183 +0.000000 1.000000 0.000000 +0.000000 0.987088 0.160181 +-0.000001 -1.000000 -0.000000 +-0.000001 -1.000000 -0.000000 +-0.000000 -1.000000 0.000001 +-0.000001 -1.000000 -0.000000 +-0.000000 -1.000000 0.000001 +-0.000000 -1.000000 0.000000 +-0.000001 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000001 -0.987087 0.160183 +-0.000001 -1.000000 -0.000000 +-0.000001 -0.987087 0.160183 +-0.000001 -0.987087 0.160183 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.160182 0.987087 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.987396 0.158267 +0.000000 0.987396 0.158267 +0.155746 0.975487 0.155460 +0.160182 0.987087 0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000000 -0.000000 +0.987088 -0.000001 0.160180 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +0.987087 -0.000000 0.160183 +0.987088 -0.000001 0.160180 +1.000000 -0.000000 -0.000000 +0.987087 -0.000000 0.160183 +1.000000 -0.000000 -0.000000 +1.000000 0.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987087 0.000000 0.160183 +-1.000000 0.000000 0.000000 +-0.987087 0.000000 0.160183 +-0.987087 0.000000 0.160183 +-1.000000 0.000000 0.000000 +-0.987087 0.000000 0.160183 +-1.000000 0.000000 0.000000 +0.987396 0.000000 0.158268 +0.709858 0.000000 0.704345 +0.709857 0.000000 0.704345 +0.709857 0.000000 0.704345 +0.987396 0.000000 0.158268 +0.987396 0.000000 0.158268 +0.000000 0.000000 1.000000 +0.162115 0.000000 0.986772 +0.173478 0.024209 0.984540 +0.018551 0.170483 0.985186 +0.000000 0.162115 0.986772 +0.000000 0.000000 1.000000 +0.173478 0.024209 0.984540 +0.018551 0.170483 0.985186 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.173478 0.024209 0.984540 +0.000000 0.000000 1.000000 +0.173478 0.024209 0.984540 +0.155927 0.141040 0.977647 +0.018551 0.170483 0.985186 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.162115 0.986772 +0.000000 0.162115 0.986772 +0.000000 0.162115 0.986772 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999195 -0.000000 -0.040116 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999195 0.000000 -0.040116 +0.999195 -0.000000 -0.040116 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +1.000000 -0.000000 0.000001 +1.000000 -0.000000 0.000001 +1.000000 0.000000 0.000001 +0.999799 0.000000 -0.020062 +0.999195 0.000000 -0.040118 +0.985935 0.159933 -0.048523 +0.985934 0.159933 -0.048522 +0.985934 0.159933 -0.048522 +0.999195 -0.000000 -0.040117 +0.999195 0.000000 -0.040118 +0.974743 0.158179 0.157659 +0.987396 0.000000 0.158268 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.987087 0.160182 0.000001 +0.974743 0.158179 0.157659 +1.000000 -0.000000 0.000001 +0.999799 0.000000 -0.020062 +0.999799 -0.000000 -0.020062 +0.999799 -0.000000 -0.020062 +1.000000 -0.000000 0.000001 +1.000000 -0.000000 0.000001 +0.999799 -0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999195 -0.000000 -0.040116 +0.999195 -0.000000 -0.040116 +0.999195 -0.000000 -0.040117 +0.999799 -0.000000 -0.020062 +0.999195 0.000000 -0.040116 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +0.999195 0.000001 -0.040116 +0.999195 0.000000 -0.040116 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020062 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +0.999799 0.000000 -0.020062 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000000 +0.999195 0.000001 -0.040116 +0.999196 -0.000000 -0.040095 +0.999196 -0.000000 -0.040096 +0.999196 -0.000000 -0.040096 +0.999195 0.000005 -0.040120 +0.999195 0.000001 -0.040116 +1.000000 -0.000000 0.000001 +0.987087 0.160182 0.000000 +0.987087 0.160182 0.000001 +0.987087 0.160182 0.000001 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000001 +0.987087 0.160182 0.000000 +0.707107 0.707107 0.000001 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.987087 0.160182 0.000001 +0.987087 0.160182 0.000000 +0.707107 0.707107 0.000001 +0.160183 0.987087 0.000000 +0.160182 0.987087 0.000000 +0.160182 0.987087 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000001 +0.160183 0.987087 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.160182 0.987087 0.000000 +0.160183 0.987087 0.000000 +1.000000 -0.000000 0.000001 +0.999799 -0.000000 -0.020062 +0.986399 0.162556 -0.024328 +0.986399 0.162556 -0.024328 +0.987087 0.160182 0.000000 +1.000000 -0.000000 0.000001 +0.986399 0.162556 -0.024328 +0.705633 0.707781 -0.033587 +0.707107 0.707107 0.000001 +0.707107 0.707107 0.000001 +0.987087 0.160182 0.000000 +0.986399 0.162556 -0.024328 +0.705633 0.707781 -0.033587 +0.161626 0.986374 -0.030703 +0.160183 0.987087 0.000000 +0.160183 0.987087 0.000000 +0.707107 0.707107 0.000001 +0.705633 0.707781 -0.033587 +0.000000 0.999610 -0.027908 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000001 0.998442 -0.055795 +-0.000001 0.998442 -0.055795 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.000001 0.998442 -0.055795 +0.000000 0.999610 -0.027908 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +0.161626 0.986374 -0.030703 +0.000000 0.999610 -0.027908 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.160183 0.987087 0.000000 +0.161626 0.986374 -0.030703 +0.159831 0.985228 -0.061474 +0.159831 0.985228 -0.061474 +0.000000 0.998442 -0.055794 +0.000000 0.998442 -0.055794 +0.000000 0.998442 -0.055795 +0.159831 0.985228 -0.061474 +0.000000 0.999610 -0.027908 +0.161626 0.986374 -0.030703 +0.159831 0.985228 -0.061474 +0.159831 0.985228 -0.061474 +0.000000 0.998442 -0.055795 +0.000000 0.999610 -0.027908 +0.161626 0.986374 -0.030703 +0.705633 0.707781 -0.033587 +0.705588 0.705376 -0.067746 +0.705588 0.705376 -0.067746 +0.159831 0.985228 -0.061474 +0.161626 0.986374 -0.030703 +0.705588 0.705376 -0.067746 +0.705633 0.707781 -0.033587 +0.986399 0.162556 -0.024328 +0.986399 0.162556 -0.024328 +0.985934 0.159933 -0.048522 +0.705588 0.705376 -0.067746 +0.999195 -0.000000 -0.040117 +0.985934 0.159933 -0.048522 +0.986399 0.162556 -0.024328 +0.986399 0.162556 -0.024328 +0.999799 -0.000000 -0.020062 +0.999195 -0.000000 -0.040117 +0.999195 0.000000 -0.040118 +0.911793 0.000000 -0.410650 +0.902713 0.144766 -0.405157 +0.902713 0.144766 -0.405157 +0.985935 0.159933 -0.048523 +0.999195 0.000000 -0.040118 +0.985935 0.159933 -0.048523 +0.902713 0.144766 -0.405157 +0.645117 0.643053 -0.412683 +0.645117 0.643053 -0.412683 +0.705588 0.705377 -0.067746 +0.985935 0.159933 -0.048523 +0.645117 0.643053 -0.412683 +0.144762 0.898824 -0.413714 +0.159831 0.985228 -0.061474 +0.159831 0.985228 -0.061474 +0.705588 0.705377 -0.067746 +0.645117 0.643053 -0.412683 +0.144762 0.898824 -0.413714 +0.000000 0.906973 -0.421189 +0.000000 0.998442 -0.055794 +0.000000 0.998442 -0.055794 +0.159831 0.985228 -0.061474 +0.144762 0.898824 -0.413714 +-0.000000 0.998441 -0.055810 +0.000000 0.999611 -0.027905 +0.000001 0.999610 -0.027908 +0.000001 0.999610 -0.027908 +0.000005 0.998442 -0.055795 +-0.000000 0.998441 -0.055810 +0.000000 0.987396 0.158267 +0.000000 0.987396 0.158267 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.987396 0.158267 +0.000000 1.000000 0.000000 +0.000000 0.999610 -0.027908 +0.000001 0.999610 -0.027908 +0.000001 0.999610 -0.027908 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000001 0.999610 -0.027908 +0.000000 0.999610 -0.027908 +-0.000001 0.998442 -0.055795 +-0.000001 0.998442 -0.055795 +0.000005 0.998442 -0.055795 +0.000001 0.999610 -0.027908 +0.000002 0.998442 -0.055798 +-0.000000 0.998441 -0.055815 +-0.000000 0.998441 -0.055810 +-0.000000 0.998441 -0.055810 +0.000005 0.998442 -0.055795 +0.000002 0.998442 -0.055798 +0.000002 0.998442 -0.055798 +0.000000 0.906973 -0.421189 +0.000000 0.906973 -0.421189 +0.000000 0.906973 -0.421189 +-0.000000 0.998441 -0.055815 +0.000002 0.998442 -0.055798 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000001 0.999610 -0.027908 +0.000000 0.999611 -0.027905 +0.000000 0.999611 -0.027905 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.987396 0.000000 0.158268 +0.987396 0.000000 0.158268 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000000 +0.987396 0.000000 0.158268 +0.999195 0.000001 -0.040116 +0.999799 0.000000 -0.020062 +0.999799 0.000000 -0.020063 +0.999799 0.000000 -0.020063 +0.999196 -0.000000 -0.040095 +0.999195 0.000001 -0.040116 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000001 +1.000000 -0.000000 0.000001 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000001 +1.000000 -0.000000 -0.000001 +1.000000 -0.000000 0.000001 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000001 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000001 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000003 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000001 +0.000000 1.000000 0.000021 +-0.000000 1.000000 0.000003 +-0.000000 1.000000 0.000003 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000001 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.293667 0.950362 -0.102818 +0.378489 0.922436 0.076533 +-0.466777 0.877351 -0.111237 +-0.466777 0.877351 -0.111237 +-0.437377 0.898427 0.039117 +0.293667 0.950362 -0.102818 +0.000000 1.000000 0.000002 +0.000000 0.928568 -0.371161 +0.053947 0.933079 -0.355603 +0.053947 0.933079 -0.355603 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +-0.083860 0.883048 -0.461729 +-0.334821 0.862577 -0.379284 +0.219047 0.944662 0.244197 +0.219047 0.944662 0.244197 +0.058021 0.917041 0.394549 +-0.083860 0.883048 -0.461729 +-0.278630 0.944534 0.173843 +-0.204871 0.931518 0.300504 +0.126855 0.942566 -0.308993 +0.126855 0.942566 -0.308993 +0.199706 0.956891 -0.210898 +-0.278630 0.944534 0.173843 +-0.437377 0.898427 0.039117 +-0.278630 0.944534 0.173843 +0.199706 0.956891 -0.210898 +0.199706 0.956891 -0.210898 +0.293667 0.950362 -0.102818 +-0.437377 0.898427 0.039117 +-0.000000 0.902777 -0.430109 +-0.083860 0.883048 -0.461729 +0.058021 0.917041 0.394549 +0.058021 0.917041 0.394549 +-0.000000 0.903393 0.428813 +-0.000000 0.902777 -0.430109 +0.219047 0.944662 0.244197 +-0.334821 0.862577 -0.379284 +-0.466777 0.877351 -0.111237 +-0.466777 0.877351 -0.111237 +0.378489 0.922436 0.076533 +0.219047 0.944662 0.244197 +-0.204871 0.931518 0.300504 +0.000000 1.000000 0.000002 +0.053947 0.933079 -0.355603 +0.053947 0.933079 -0.355603 +0.126855 0.942566 -0.308993 +-0.204871 0.931518 0.300504 +0.984855 0.000001 0.173380 +0.924386 0.345298 0.162108 +0.906193 0.386267 -0.172082 +0.906193 0.386267 -0.172082 +0.973923 0.000000 -0.226877 +0.984855 0.000001 0.173380 +-0.965948 0.000000 0.258737 +-0.876796 0.404449 0.260095 +-0.922754 0.317517 -0.218422 +-0.922754 0.317517 -0.218422 +-0.972507 0.000000 -0.232874 +-0.965948 0.000000 0.258737 +0.000000 0.000000 1.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.165253 0.000000 -0.986251 +0.145080 0.399992 -0.904963 +-0.000000 0.389580 -0.920992 +-0.000000 0.389580 -0.920992 +0.000000 0.000000 -1.000000 +0.165253 0.000000 -0.986251 +-0.661497 0.000000 -0.749948 +-0.628453 0.312262 -0.712418 +-0.161327 0.320071 -0.933557 +-0.161327 0.320071 -0.933557 +-0.174458 0.000000 -0.984665 +-0.661497 0.000000 -0.749948 +0.139943 0.000000 0.990160 +0.134000 0.341445 0.930301 +0.629331 0.383170 0.676109 +0.629331 0.383170 0.676109 +0.682763 0.000001 0.730640 +0.139943 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000001 0.480135 -0.877194 +-0.472044 0.840449 -0.266121 +-0.472044 0.840449 -0.266121 +-0.865983 0.000000 -0.500074 +0.000000 0.000000 -1.000000 +0.973923 0.000000 -0.226877 +0.906193 0.386267 -0.172082 +0.686198 0.460064 -0.563448 +0.686198 0.460064 -0.563448 +0.766123 0.000000 -0.642694 +0.973923 0.000000 -0.226877 +-0.865983 0.000000 -0.500074 +-0.472044 0.840449 -0.266121 +-0.876796 0.404449 0.260095 +-0.876796 0.404449 0.260095 +-0.965948 0.000000 0.258737 +-0.865983 0.000000 -0.500074 +-0.000000 0.000000 1.000000 +-0.000000 0.335574 0.942014 +0.134000 0.341445 0.930301 +0.134000 0.341445 0.930301 +0.139943 0.000000 0.990160 +-0.000000 0.000000 1.000000 +-0.174458 0.000000 -0.984665 +-0.161327 0.320071 -0.933557 +-0.000000 0.335181 -0.942154 +-0.000000 0.335181 -0.942154 +0.000000 0.000000 -1.000000 +-0.174458 0.000000 -0.984665 +-0.972507 0.000000 -0.232874 +-0.922754 0.317517 -0.218422 +-0.628453 0.312262 -0.712418 +-0.628453 0.312262 -0.712418 +-0.661497 0.000000 -0.749948 +-0.972507 0.000000 -0.232874 +0.682763 0.000001 0.730640 +0.629331 0.383170 0.676109 +0.924386 0.345298 0.162108 +0.924386 0.345298 0.162108 +0.984855 0.000001 0.173380 +0.682763 0.000001 0.730640 +0.446772 0.000000 -0.894648 +0.391985 0.437360 -0.809360 +0.145080 0.399992 -0.904963 +0.145080 0.399992 -0.904963 +0.165253 0.000000 -0.986251 +0.446772 0.000000 -0.894648 +0.766123 0.000000 -0.642694 +0.686198 0.460064 -0.563448 +0.391985 0.437360 -0.809360 +0.391985 0.437360 -0.809360 +0.446772 0.000000 -0.894648 +0.766123 0.000000 -0.642694 +-0.437377 0.898427 0.039117 +-0.466777 0.877351 -0.111237 +-0.922754 0.317517 -0.218422 +-0.922754 0.317517 -0.218422 +-0.876796 0.404449 0.260095 +-0.437377 0.898427 0.039117 +0.378489 0.922436 0.076533 +0.293667 0.950362 -0.102818 +0.906193 0.386267 -0.172082 +0.906193 0.386267 -0.172082 +0.924386 0.345298 0.162108 +0.378489 0.922436 0.076533 +0.000000 0.960502 0.278273 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +-0.016761 0.961573 0.274037 +0.000000 0.960502 0.278273 +0.145080 0.399992 -0.904963 +0.053947 0.933079 -0.355603 +0.000000 0.928568 -0.371161 +0.000000 0.928568 -0.371161 +-0.000000 0.389580 -0.920992 +0.145080 0.399992 -0.904963 +0.058021 0.917041 0.394549 +0.219047 0.944662 0.244197 +0.629331 0.383170 0.676109 +0.629331 0.383170 0.676109 +0.134000 0.341445 0.930301 +0.058021 0.917041 0.394549 +-0.334821 0.862577 -0.379284 +-0.083860 0.883048 -0.461729 +-0.161327 0.320071 -0.933557 +-0.161327 0.320071 -0.933557 +-0.628453 0.312262 -0.712418 +-0.334821 0.862577 -0.379284 +0.199706 0.956891 -0.210898 +0.126855 0.942566 -0.308993 +0.391985 0.437360 -0.809360 +0.391985 0.437360 -0.809360 +0.686198 0.460064 -0.563448 +0.199706 0.956891 -0.210898 +0.293667 0.950362 -0.102818 +0.199706 0.956891 -0.210898 +0.686198 0.460064 -0.563448 +0.686198 0.460064 -0.563448 +0.906193 0.386267 -0.172082 +0.293667 0.950362 -0.102818 +-0.278630 0.944534 0.173843 +-0.437377 0.898427 0.039117 +-0.876796 0.404449 0.260095 +-0.876796 0.404449 0.260095 +-0.472044 0.840449 -0.266121 +-0.278630 0.944534 0.173843 +-0.000000 0.903393 0.428813 +0.058021 0.917041 0.394549 +0.134000 0.341445 0.930301 +0.134000 0.341445 0.930301 +-0.000000 0.335574 0.942014 +-0.000000 0.903393 0.428813 +-0.161327 0.320071 -0.933557 +-0.083860 0.883048 -0.461729 +-0.000000 0.902777 -0.430109 +-0.000000 0.902777 -0.430109 +-0.000000 0.335181 -0.942154 +-0.161327 0.320071 -0.933557 +0.629331 0.383170 0.676109 +0.219047 0.944662 0.244197 +0.378489 0.922436 0.076533 +0.378489 0.922436 0.076533 +0.924386 0.345298 0.162108 +0.629331 0.383170 0.676109 +-0.922754 0.317517 -0.218422 +-0.466777 0.877351 -0.111237 +-0.334821 0.862577 -0.379284 +-0.334821 0.862577 -0.379284 +-0.628453 0.312262 -0.712418 +-0.922754 0.317517 -0.218422 +0.126855 0.942566 -0.308993 +0.053947 0.933079 -0.355603 +0.145080 0.399992 -0.904963 +0.145080 0.399992 -0.904963 +0.391985 0.437360 -0.809360 +0.126855 0.942566 -0.308993 +-0.204871 0.931518 0.300504 +-0.472044 0.840449 -0.266121 +-0.016761 0.961573 0.274037 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.482408 0.875946 +0.000000 0.960502 0.278273 +-0.016761 0.961573 0.274037 +-0.016761 0.961573 0.274037 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +-0.016761 0.961573 0.274037 +0.000000 0.999997 -0.002593 +0.000000 0.999997 -0.002593 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +-0.016761 0.961573 0.274037 +0.000000 1.000000 0.000002 +-0.204871 0.931518 0.300504 +-0.204871 0.931518 0.300504 +-0.278630 0.944534 0.173843 +-0.472044 0.840449 -0.266121 +0.000001 0.480135 -0.877194 +0.000000 0.999997 -0.002593 +-0.016761 0.961573 0.274037 +-0.016761 0.961573 0.274037 +-0.472044 0.840449 -0.266121 +0.000001 0.480135 -0.877194 +-0.293669 0.950361 -0.102818 +0.437376 0.898427 0.039117 +0.466777 0.877352 -0.111236 +0.466777 0.877352 -0.111236 +-0.378490 0.922436 0.076533 +-0.293669 0.950361 -0.102818 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +-0.053947 0.933079 -0.355603 +-0.053947 0.933079 -0.355603 +0.000000 0.928568 -0.371161 +0.000000 1.000000 0.000002 +0.083860 0.883048 -0.461729 +-0.058021 0.917041 0.394549 +-0.219047 0.944662 0.244197 +-0.219047 0.944662 0.244197 +0.334821 0.862576 -0.379284 +0.083860 0.883048 -0.461729 +0.278630 0.944534 0.173843 +-0.199706 0.956891 -0.210898 +-0.126855 0.942566 -0.308994 +-0.126855 0.942566 -0.308994 +0.204871 0.931518 0.300504 +0.278630 0.944534 0.173843 +0.437376 0.898427 0.039117 +-0.293669 0.950361 -0.102818 +-0.199706 0.956891 -0.210898 +-0.199706 0.956891 -0.210898 +0.278630 0.944534 0.173843 +0.437376 0.898427 0.039117 +-0.000000 0.902777 -0.430109 +-0.000000 0.903393 0.428813 +-0.058021 0.917041 0.394549 +-0.058021 0.917041 0.394549 +0.083860 0.883048 -0.461729 +-0.000000 0.902777 -0.430109 +-0.219047 0.944662 0.244197 +-0.378490 0.922436 0.076533 +0.466777 0.877352 -0.111236 +0.466777 0.877352 -0.111236 +0.334821 0.862576 -0.379284 +-0.219047 0.944662 0.244197 +0.204871 0.931518 0.300504 +-0.126855 0.942566 -0.308994 +-0.053947 0.933079 -0.355603 +-0.053947 0.933079 -0.355603 +0.000000 1.000000 0.000002 +0.204871 0.931518 0.300504 +-0.984855 0.000000 0.173382 +-0.973923 0.000000 -0.226877 +-0.906194 0.386265 -0.172082 +-0.906194 0.386265 -0.172082 +-0.924387 0.345297 0.162109 +-0.984855 0.000000 0.173382 +0.965948 0.000000 0.258737 +0.972507 0.000000 -0.232875 +0.922754 0.317518 -0.218422 +0.922754 0.317518 -0.218422 +0.876797 0.404449 0.260094 +0.965948 0.000000 0.258737 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.000000 1.000000 +-0.165253 0.000000 -0.986251 +0.000000 0.000000 -1.000000 +-0.000000 0.389580 -0.920992 +-0.000000 0.389580 -0.920992 +-0.145080 0.399992 -0.904963 +-0.165253 0.000000 -0.986251 +0.661497 0.000000 -0.749948 +0.174458 0.000000 -0.984665 +0.161327 0.320071 -0.933557 +0.161327 0.320071 -0.933557 +0.628453 0.312262 -0.712418 +0.661497 0.000000 -0.749948 +-0.139942 0.000000 0.990160 +-0.682761 0.000000 0.730642 +-0.629331 0.383170 0.676109 +-0.629331 0.383170 0.676109 +-0.133999 0.341445 0.930301 +-0.139942 0.000000 0.990160 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.865983 0.000000 -0.500074 +0.472044 0.840449 -0.266121 +0.472044 0.840449 -0.266121 +-0.000001 0.480135 -0.877194 +0.000000 0.000000 -1.000000 +-0.973923 0.000000 -0.226877 +-0.766123 0.000000 -0.642694 +-0.686198 0.460063 -0.563448 +-0.686198 0.460063 -0.563448 +-0.906194 0.386265 -0.172082 +-0.973923 0.000000 -0.226877 +0.865983 0.000000 -0.500074 +0.965948 0.000000 0.258737 +0.876797 0.404449 0.260094 +0.876797 0.404449 0.260094 +0.472044 0.840449 -0.266121 +0.865983 0.000000 -0.500074 +-0.000000 0.000000 1.000000 +-0.139942 0.000000 0.990160 +-0.133999 0.341445 0.930301 +-0.133999 0.341445 0.930301 +-0.000000 0.335574 0.942014 +-0.000000 0.000000 1.000000 +0.174458 0.000000 -0.984665 +0.000000 0.000000 -1.000000 +-0.000000 0.335181 -0.942154 +-0.000000 0.335181 -0.942154 +0.161327 0.320071 -0.933557 +0.174458 0.000000 -0.984665 +0.972507 0.000000 -0.232875 +0.661497 0.000000 -0.749948 +0.628453 0.312262 -0.712418 +0.628453 0.312262 -0.712418 +0.922754 0.317518 -0.218422 +0.972507 0.000000 -0.232875 +-0.682761 0.000000 0.730642 +-0.984855 0.000000 0.173382 +-0.924387 0.345297 0.162109 +-0.924387 0.345297 0.162109 +-0.629331 0.383170 0.676109 +-0.682761 0.000000 0.730642 +-0.446771 0.000000 -0.894648 +-0.165253 0.000000 -0.986251 +-0.145080 0.399992 -0.904963 +-0.145080 0.399992 -0.904963 +-0.391985 0.437360 -0.809361 +-0.446771 0.000000 -0.894648 +-0.766123 0.000000 -0.642694 +-0.446771 0.000000 -0.894648 +-0.391985 0.437360 -0.809361 +-0.391985 0.437360 -0.809361 +-0.686198 0.460063 -0.563448 +-0.766123 0.000000 -0.642694 +0.437376 0.898427 0.039117 +0.876797 0.404449 0.260094 +0.922754 0.317518 -0.218422 +0.922754 0.317518 -0.218422 +0.466777 0.877352 -0.111236 +0.437376 0.898427 0.039117 +-0.378490 0.922436 0.076533 +-0.924387 0.345297 0.162109 +-0.906194 0.386265 -0.172082 +-0.906194 0.386265 -0.172082 +-0.293669 0.950361 -0.102818 +-0.378490 0.922436 0.076533 +0.000000 0.960502 0.278273 +0.016761 0.961573 0.274037 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.960502 0.278273 +-0.145080 0.399992 -0.904963 +-0.000000 0.389580 -0.920992 +0.000000 0.928568 -0.371161 +0.000000 0.928568 -0.371161 +-0.053947 0.933079 -0.355603 +-0.145080 0.399992 -0.904963 +-0.058021 0.917041 0.394549 +-0.133999 0.341445 0.930301 +-0.629331 0.383170 0.676109 +-0.629331 0.383170 0.676109 +-0.219047 0.944662 0.244197 +-0.058021 0.917041 0.394549 +0.334821 0.862576 -0.379284 +0.628453 0.312262 -0.712418 +0.161327 0.320071 -0.933557 +0.161327 0.320071 -0.933557 +0.083860 0.883048 -0.461729 +0.334821 0.862576 -0.379284 +-0.199706 0.956891 -0.210898 +-0.686198 0.460063 -0.563448 +-0.391985 0.437360 -0.809361 +-0.391985 0.437360 -0.809361 +-0.126855 0.942566 -0.308994 +-0.199706 0.956891 -0.210898 +-0.293669 0.950361 -0.102818 +-0.906194 0.386265 -0.172082 +-0.686198 0.460063 -0.563448 +-0.686198 0.460063 -0.563448 +-0.199706 0.956891 -0.210898 +-0.293669 0.950361 -0.102818 +0.278630 0.944534 0.173843 +0.472044 0.840449 -0.266121 +0.876797 0.404449 0.260094 +0.876797 0.404449 0.260094 +0.437376 0.898427 0.039117 +0.278630 0.944534 0.173843 +-0.000000 0.903393 0.428813 +-0.000000 0.335574 0.942014 +-0.133999 0.341445 0.930301 +-0.133999 0.341445 0.930301 +-0.058021 0.917041 0.394549 +-0.000000 0.903393 0.428813 +0.161327 0.320071 -0.933557 +-0.000000 0.335181 -0.942154 +-0.000000 0.902777 -0.430109 +-0.000000 0.902777 -0.430109 +0.083860 0.883048 -0.461729 +0.161327 0.320071 -0.933557 +-0.629331 0.383170 0.676109 +-0.924387 0.345297 0.162109 +-0.378490 0.922436 0.076533 +-0.378490 0.922436 0.076533 +-0.219047 0.944662 0.244197 +-0.629331 0.383170 0.676109 +0.922754 0.317518 -0.218422 +0.628453 0.312262 -0.712418 +0.334821 0.862576 -0.379284 +0.334821 0.862576 -0.379284 +0.466777 0.877352 -0.111236 +0.922754 0.317518 -0.218422 +-0.126855 0.942566 -0.308994 +-0.391985 0.437360 -0.809361 +-0.145080 0.399992 -0.904963 +-0.145080 0.399992 -0.904963 +-0.053947 0.933079 -0.355603 +-0.126855 0.942566 -0.308994 +0.204871 0.931518 0.300504 +0.016761 0.961573 0.274037 +0.472044 0.840449 -0.266121 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.016761 0.961573 0.274037 +0.016761 0.961573 0.274037 +0.000000 0.960502 0.278273 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.482408 0.875946 +0.000000 0.999997 -0.002593 +0.000000 0.999997 -0.002593 +0.016761 0.961573 0.274037 +0.000000 0.482408 0.875946 +0.016761 0.961573 0.274037 +0.204871 0.931518 0.300504 +0.000000 1.000000 0.000002 +0.204871 0.931518 0.300504 +0.472044 0.840449 -0.266121 +0.278630 0.944534 0.173843 +-0.000001 0.480135 -0.877194 +0.472044 0.840449 -0.266121 +0.016761 0.961573 0.274037 +0.016761 0.961573 0.274037 +0.000000 0.999997 -0.002593 +-0.000001 0.480135 -0.877194 +0.162115 0.000000 0.986772 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.162115 0.000000 0.986772 +0.162115 0.000000 0.986772 +0.162115 0.000000 0.986772 +0.162115 -0.000000 0.986772 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.162115 0.000000 0.986772 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.987088 0.160179 0.000000 +-0.987088 0.160179 0.000000 +-0.987088 0.160179 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.090945 0.995856 +0.000000 0.136135 0.990690 +0.000000 0.136135 0.990690 +0.000000 0.090945 0.995856 +0.000000 0.090945 0.995856 +0.000000 0.136135 0.990690 +-0.011116 0.125442 0.992039 +0.000000 0.090945 0.995856 +0.000000 0.136135 0.990690 +-0.011116 0.125442 0.992039 +0.000000 0.136135 0.990690 +-0.024596 0.112431 0.993355 +-0.962160 0.000000 0.272486 +-0.962160 0.000000 0.272486 +-0.943771 0.131277 0.303417 +-0.943771 0.131277 0.303417 +-0.934508 0.171543 0.311877 +-0.962160 0.000000 0.272486 +-0.067300 0.649220 -0.757617 +-0.128270 0.611138 -0.781062 +0.000000 0.686714 -0.726928 +0.000000 0.686714 -0.726928 +0.000000 0.686714 -0.726928 +-0.067300 0.649220 -0.757617 +-0.163219 0.984624 -0.062245 +0.000000 0.998433 -0.055964 +0.000000 0.998433 -0.055963 +0.000000 0.998433 -0.055963 +-0.159866 0.985177 -0.062205 +-0.163219 0.984624 -0.062245 +-0.999054 -0.000000 -0.043479 +-0.985762 0.159898 -0.052024 +-0.986521 0.155074 -0.052242 +-0.986521 0.155074 -0.052242 +-0.999027 0.000000 -0.044103 +-0.999054 -0.000000 -0.043479 +-0.999038 0.000000 -0.043860 +-0.999038 0.000000 -0.043860 +-0.999038 0.000000 -0.043860 +-0.999038 0.000000 -0.043860 +-0.999038 0.000000 -0.043860 +-0.999038 0.000000 -0.043860 +-0.999054 0.000000 -0.043479 +-0.999054 -0.000000 -0.043486 +-0.999027 0.000000 -0.044102 +-0.999027 0.000000 -0.044102 +-0.999027 0.000000 -0.044103 +-0.999054 0.000000 -0.043479 +-0.691128 0.000001 -0.722733 +-0.613769 0.129384 -0.778812 +-0.653289 0.067036 -0.754135 +-0.653289 0.067036 -0.754135 +-0.691128 0.000001 -0.722732 +-0.691128 0.000001 -0.722733 +-0.682748 0.000000 -0.730654 +-0.682748 0.000000 -0.730654 +-0.682748 0.000000 -0.730654 +-0.682748 0.000000 -0.730654 +-0.682748 0.000000 -0.730654 +-0.682748 0.000000 -0.730654 +-0.691128 0.000000 -0.722732 +-0.691128 0.000000 -0.722732 +-0.691128 0.000000 -0.722732 +-0.691128 0.000000 -0.722732 +-0.691128 0.000000 -0.722733 +-0.691128 0.000000 -0.722732 +-0.217362 -0.970528 -0.104062 +-0.217362 -0.970528 -0.104062 +-0.217362 -0.970528 -0.104062 +-0.216100 -0.970831 -0.103869 +-0.216100 -0.970831 -0.103869 +-0.216100 -0.970831 -0.103869 +-0.205506 -0.932072 -0.298345 +-0.205506 -0.932072 -0.298345 +-0.205506 -0.932072 -0.298345 +-0.207347 -0.926207 -0.314878 +-0.207347 -0.926207 -0.314878 +-0.207347 -0.926207 -0.314878 +-0.207482 0.926773 -0.313117 +-0.207482 0.926773 -0.313117 +-0.207482 0.926773 -0.313117 +-0.211048 0.929400 -0.302779 +-0.211048 0.929400 -0.302779 +-0.211048 0.929400 -0.302779 +-0.216091 0.970684 -0.105248 +-0.216091 0.970684 -0.105248 +-0.216091 0.970684 -0.105248 +-0.217176 0.970455 -0.105127 +-0.217176 0.970455 -0.105127 +-0.217176 0.970455 -0.105127 +-0.194186 -0.000000 -0.980965 +-0.194186 -0.000000 -0.980965 +-0.194186 -0.000000 -0.980965 +-0.194187 0.000000 -0.980965 +-0.194187 0.000000 -0.980965 +-0.194187 0.000000 -0.980965 +-0.217172 -0.970440 -0.105272 +-0.217172 -0.970440 -0.105272 +-0.217172 -0.970440 -0.105272 +-0.216066 -0.970705 -0.105103 +-0.216066 -0.970705 -0.105102 +-0.216066 -0.970705 -0.105103 +-0.210116 -0.925296 -0.315719 +-0.210116 -0.925296 -0.315719 +-0.210116 -0.925296 -0.315719 +-0.208395 -0.930880 -0.300057 +-0.208395 -0.930880 -0.300057 +-0.208395 -0.930880 -0.300057 +-0.156367 0.985741 -0.062154 +-0.159866 0.985177 -0.062205 +0.000000 0.998433 -0.055963 +0.000000 0.998433 -0.055963 +0.000000 0.998433 -0.055963 +-0.156367 0.985741 -0.062154 +-0.160183 0.987087 0.000000 +-0.160183 0.987087 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.160183 0.987087 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.127993 0.011020 0.991714 +-0.113787 0.025124 0.993187 +-0.139053 0.000000 0.990285 +-0.139053 0.000000 0.990285 +-0.139053 0.000000 0.990285 +-0.127993 0.011020 0.991714 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.999067 0.000000 -0.043190 +-0.984967 0.164786 -0.051814 +-0.985762 0.159898 -0.052024 +-0.999067 0.000000 -0.043190 +-0.985762 0.159898 -0.052024 +-0.999054 -0.000000 -0.043479 +-0.999067 0.000000 -0.043190 +-0.999054 -0.000000 -0.043479 +-0.999054 -0.000000 -0.043486 +-0.999067 0.000000 -0.043190 +-0.999054 -0.000000 -0.043486 +-0.999054 0.000000 -0.043479 +-0.999067 0.000000 -0.043190 +-0.999054 0.000000 -0.043479 +-0.999067 0.000000 -0.043191 +-0.194281 -0.000000 -0.980946 +-0.194281 -0.000000 -0.980946 +-0.194281 -0.000000 -0.980946 +-0.194282 0.000000 -0.980946 +-0.194282 0.000000 -0.980946 +-0.194282 0.000000 -0.980946 +0.000000 0.964133 0.265420 +-0.172666 0.936050 0.306588 +-0.130685 0.945774 0.297376 +-0.130685 0.945774 0.297376 +0.000000 0.964133 0.265419 +0.000000 0.964133 0.265420 +-0.130685 0.945774 0.297376 +0.000000 0.964133 0.265419 +-0.000000 0.964133 0.265419 +-0.000000 0.964133 0.265419 +0.000000 0.964133 0.265419 +-0.130685 0.945774 0.297376 +0.000000 0.964133 0.265420 +0.000000 0.964133 0.265420 +-0.000000 0.964133 0.265419 +-0.000000 0.964133 0.265419 +0.000000 0.964133 0.265419 +0.000000 0.964133 0.265420 +0.000000 0.090945 0.995856 +0.000000 0.090945 0.995856 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.090945 0.995856 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.705506 0.705204 -0.070341 +-0.985762 0.159898 -0.052024 +-0.984967 0.164786 -0.051814 +-0.984967 0.164786 -0.051814 +-0.703602 0.707133 -0.070051 +-0.705506 0.705204 -0.070341 +-0.707109 0.707104 0.000000 +-0.160183 0.987087 0.000000 +-0.160183 0.987087 0.000000 +-0.160183 0.987087 0.000000 +-0.707109 0.707104 0.000000 +-0.707109 0.707104 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.068966 0.069265 0.995212 +-0.113787 0.025124 0.993187 +-0.127993 0.011020 0.991714 +-0.127993 0.011020 0.991714 +-0.069489 0.068753 0.995211 +-0.068966 0.069265 0.995212 +-0.656525 0.658835 0.367303 +-0.130685 0.945774 0.297376 +-0.172666 0.936050 0.306588 +-0.172666 0.936050 0.306588 +-0.658526 0.656828 0.367316 +-0.656525 0.658835 0.367303 +-0.393996 0.394837 -0.829983 +-0.128270 0.611138 -0.781062 +-0.067300 0.649220 -0.757617 +-0.067300 0.649220 -0.757617 +-0.395300 0.393544 -0.829977 +-0.393996 0.394837 -0.829983 +-0.707078 0.703597 -0.070651 +-0.986521 0.155074 -0.052242 +-0.985762 0.159898 -0.052024 +-0.985762 0.159898 -0.052024 +-0.705506 0.705204 -0.070341 +-0.707078 0.703597 -0.070651 +-0.159866 0.985177 -0.062205 +-0.705506 0.705204 -0.070341 +-0.703602 0.707133 -0.070051 +-0.703602 0.707133 -0.070051 +-0.163219 0.984624 -0.062245 +-0.159866 0.985177 -0.062205 +-0.987088 0.160179 0.000000 +-0.707109 0.707104 0.000000 +-0.707109 0.707104 0.000000 +-0.707109 0.707104 0.000000 +-0.987088 0.160179 0.000000 +-0.987088 0.160179 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.024596 0.112431 0.993355 +-0.068966 0.069265 0.995212 +-0.069489 0.068753 0.995211 +-0.069489 0.068753 0.995211 +-0.011116 0.125442 0.992039 +-0.024596 0.112431 0.993355 +-0.943771 0.131277 0.303417 +-0.656525 0.658835 0.367303 +-0.658526 0.656828 0.367316 +-0.658526 0.656828 0.367316 +-0.934508 0.171543 0.311877 +-0.943771 0.131277 0.303417 +-0.613769 0.129384 -0.778812 +-0.393996 0.394837 -0.829983 +-0.395300 0.393544 -0.829977 +-0.395300 0.393544 -0.829977 +-0.653289 0.067036 -0.754135 +-0.613769 0.129384 -0.778812 +-0.156367 0.985741 -0.062154 +-0.707078 0.703597 -0.070651 +-0.705506 0.705204 -0.070341 +-0.705506 0.705204 -0.070341 +-0.159866 0.985177 -0.062205 +-0.156367 0.985741 -0.062154 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-0.999042 0.000000 -0.043762 +-1.000000 0.000000 0.000000 +-0.987087 -0.160185 0.000000 +-0.987087 -0.160185 0.000000 +-0.987087 -0.160185 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.011116 -0.125442 0.992039 +-0.024597 -0.112430 0.993355 +0.000000 -0.136135 0.990690 +0.000000 -0.136135 0.990690 +0.000000 -0.136135 0.990690 +0.000000 -0.090945 0.995856 +0.000000 -0.136135 0.990690 +0.000000 -0.090945 0.995856 +0.000000 -0.090945 0.995856 +-0.011116 -0.125442 0.992039 +0.000000 -0.136135 0.990690 +0.000000 -0.090945 0.995856 +-0.962160 0.000000 0.272486 +-0.934506 -0.171549 0.311880 +-0.943772 -0.131273 0.303417 +-0.943772 -0.131273 0.303417 +-0.962160 0.000000 0.272486 +-0.962160 0.000000 0.272486 +-0.067299 -0.649220 -0.757617 +0.000000 -0.686714 -0.726928 +0.000000 -0.686714 -0.726928 +0.000000 -0.686714 -0.726928 +-0.128271 -0.611136 -0.781063 +-0.067299 -0.649220 -0.757617 +-0.163219 -0.984624 -0.062245 +-0.159864 -0.985177 -0.062205 +-0.000000 -0.998433 -0.055963 +-0.000000 -0.998433 -0.055963 +0.000000 -0.998433 -0.055964 +-0.163219 -0.984624 -0.062245 +-0.999054 0.000000 -0.043479 +-0.999027 0.000000 -0.044102 +-0.986520 -0.155080 -0.052242 +-0.986520 -0.155080 -0.052242 +-0.985763 -0.159892 -0.052023 +-0.999054 0.000000 -0.043479 +-0.999038 0.000000 -0.043860 +-0.999038 0.000001 -0.043860 +-0.999038 0.000001 -0.043860 +-0.999038 0.000001 -0.043860 +-0.999038 0.000000 -0.043860 +-0.999038 0.000000 -0.043860 +-0.999054 -0.000000 -0.043479 +-0.999027 0.000000 -0.044103 +-0.999027 -0.000000 -0.044102 +-0.999027 -0.000000 -0.044102 +-0.999054 0.000000 -0.043486 +-0.999054 -0.000000 -0.043479 +-0.691122 0.000000 -0.722738 +-0.691122 0.000000 -0.722738 +-0.653287 -0.067038 -0.754137 +-0.653287 -0.067038 -0.754137 +-0.613766 -0.129388 -0.778813 +-0.691122 0.000000 -0.722738 +-0.682748 0.000000 -0.730654 +-0.682748 0.000000 -0.730654 +-0.682742 0.000001 -0.730659 +-0.682742 0.000001 -0.730659 +-0.682742 0.000001 -0.730659 +-0.682748 0.000000 -0.730654 +-0.691128 0.000000 -0.722732 +-0.691128 0.000000 -0.722733 +-0.691128 0.000000 -0.722732 +-0.691128 0.000000 -0.722732 +-0.691128 0.000000 -0.722732 +-0.691128 0.000000 -0.722732 +-0.216100 0.970831 -0.103869 +-0.216100 0.970831 -0.103869 +-0.216100 0.970831 -0.103869 +-0.217362 0.970528 -0.104062 +-0.217362 0.970528 -0.104062 +-0.217362 0.970528 -0.104062 +-0.207347 0.926207 -0.314879 +-0.207347 0.926207 -0.314879 +-0.207347 0.926207 -0.314879 +-0.205506 0.932072 -0.298345 +-0.205506 0.932072 -0.298345 +-0.205506 0.932072 -0.298345 +-0.211048 -0.929400 -0.302779 +-0.211048 -0.929400 -0.302779 +-0.211048 -0.929400 -0.302779 +-0.207481 -0.926773 -0.313119 +-0.207481 -0.926773 -0.313119 +-0.207481 -0.926773 -0.313119 +-0.217175 -0.970455 -0.105127 +-0.217175 -0.970455 -0.105127 +-0.217175 -0.970455 -0.105127 +-0.216091 -0.970684 -0.105248 +-0.216091 -0.970684 -0.105248 +-0.216091 -0.970684 -0.105248 +-0.194187 0.000000 -0.980965 +-0.194187 0.000000 -0.980965 +-0.194187 0.000000 -0.980965 +-0.194186 0.000000 -0.980965 +-0.194186 0.000000 -0.980965 +-0.194186 0.000000 -0.980965 +-0.216066 0.970705 -0.105102 +-0.216066 0.970705 -0.105102 +-0.216066 0.970705 -0.105102 +-0.217172 0.970440 -0.105272 +-0.217172 0.970440 -0.105272 +-0.217172 0.970440 -0.105272 +-0.208395 0.930879 -0.300060 +-0.208395 0.930879 -0.300060 +-0.208395 0.930879 -0.300060 +-0.210116 0.925295 -0.315722 +-0.210116 0.925295 -0.315722 +-0.210116 0.925295 -0.315722 +-0.156369 -0.985741 -0.062154 +0.000000 -0.998433 -0.055963 +-0.000000 -0.998433 -0.055963 +-0.000000 -0.998433 -0.055963 +-0.159864 -0.985177 -0.062205 +-0.156369 -0.985741 -0.062154 +-0.160185 -0.987087 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.160185 -0.987087 0.000000 +-0.160185 -0.987087 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.127993 -0.011020 0.991714 +-0.139053 0.000000 0.990285 +-0.139053 0.000000 0.990285 +-0.139053 0.000000 0.990285 +-0.113787 -0.025125 0.993187 +-0.127993 -0.011020 0.991714 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.682999 0.000000 -0.730420 +-0.999067 0.000000 -0.043190 +-0.999067 0.000000 -0.043191 +-0.999054 -0.000000 -0.043479 +-0.999067 0.000000 -0.043190 +-0.999054 -0.000000 -0.043479 +-0.999054 0.000000 -0.043486 +-0.999067 0.000000 -0.043190 +-0.999054 0.000000 -0.043486 +-0.999054 0.000000 -0.043479 +-0.999067 0.000000 -0.043190 +-0.999054 0.000000 -0.043479 +-0.985763 -0.159892 -0.052023 +-0.999067 0.000000 -0.043190 +-0.985763 -0.159892 -0.052023 +-0.984968 -0.164785 -0.051812 +-0.194282 0.000000 -0.980946 +-0.194282 0.000000 -0.980946 +-0.194282 0.000000 -0.980946 +-0.194281 0.000000 -0.980946 +-0.194281 0.000000 -0.980946 +-0.194281 0.000000 -0.980946 +0.000000 -0.964133 0.265420 +0.000000 -0.964133 0.265419 +-0.130684 -0.945775 0.297375 +-0.130684 -0.945775 0.297375 +-0.172666 -0.936050 0.306588 +0.000000 -0.964133 0.265420 +-0.130684 -0.945775 0.297375 +0.000000 -0.964133 0.265419 +-0.000000 -0.964133 0.265419 +-0.000000 -0.964133 0.265419 +0.000000 -0.964133 0.265419 +-0.130684 -0.945775 0.297375 +0.000000 -0.964133 0.265420 +0.000000 -0.964133 0.265419 +-0.000000 -0.964133 0.265419 +-0.000000 -0.964133 0.265419 +0.000000 -0.964133 0.265420 +0.000000 -0.964133 0.265420 +0.000000 -0.090945 0.995856 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.090945 0.995856 +0.000000 -0.090945 0.995856 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.974308 0.000000 -0.225219 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.975766 0.000000 -0.218815 +-0.705509 -0.705202 -0.070340 +-0.703602 -0.707134 -0.070049 +-0.984968 -0.164785 -0.051812 +-0.984968 -0.164785 -0.051812 +-0.985763 -0.159892 -0.052023 +-0.705509 -0.705202 -0.070340 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.160185 -0.987087 0.000000 +-0.160185 -0.987087 0.000000 +-0.160185 -0.987087 0.000000 +-0.707106 -0.707107 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.068965 -0.069266 0.995212 +-0.069489 -0.068754 0.995211 +-0.127993 -0.011020 0.991714 +-0.127993 -0.011020 0.991714 +-0.113787 -0.025125 0.993187 +-0.068965 -0.069266 0.995212 +-0.656529 -0.658832 0.367302 +-0.658522 -0.656831 0.367316 +-0.172666 -0.936050 0.306588 +-0.172666 -0.936050 0.306588 +-0.130684 -0.945775 0.297375 +-0.656529 -0.658832 0.367302 +-0.393994 -0.394838 -0.829983 +-0.395296 -0.393547 -0.829977 +-0.067299 -0.649220 -0.757617 +-0.067299 -0.649220 -0.757617 +-0.128271 -0.611136 -0.781063 +-0.393994 -0.394838 -0.829983 +-0.707075 -0.703600 -0.070651 +-0.705509 -0.705202 -0.070340 +-0.985763 -0.159892 -0.052023 +-0.985763 -0.159892 -0.052023 +-0.986520 -0.155080 -0.052242 +-0.707075 -0.703600 -0.070651 +-0.159864 -0.985177 -0.062205 +-0.163219 -0.984624 -0.062245 +-0.703602 -0.707134 -0.070049 +-0.703602 -0.707134 -0.070049 +-0.705509 -0.705202 -0.070340 +-0.159864 -0.985177 -0.062205 +-0.987087 -0.160185 0.000000 +-0.987087 -0.160185 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.987087 -0.160185 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.024597 -0.112430 0.993355 +-0.011116 -0.125442 0.992039 +-0.069489 -0.068754 0.995211 +-0.069489 -0.068754 0.995211 +-0.068965 -0.069266 0.995212 +-0.024597 -0.112430 0.993355 +-0.943772 -0.131273 0.303417 +-0.934506 -0.171549 0.311880 +-0.658522 -0.656831 0.367316 +-0.658522 -0.656831 0.367316 +-0.656529 -0.658832 0.367302 +-0.943772 -0.131273 0.303417 +-0.613766 -0.129388 -0.778813 +-0.653287 -0.067038 -0.754137 +-0.395296 -0.393547 -0.829977 +-0.395296 -0.393547 -0.829977 +-0.393994 -0.394838 -0.829983 +-0.613766 -0.129388 -0.778813 +-0.156369 -0.985741 -0.062154 +-0.159864 -0.985177 -0.062205 +-0.705509 -0.705202 -0.070340 +-0.705509 -0.705202 -0.070340 +-0.707075 -0.703600 -0.070651 +-0.156369 -0.985741 -0.062154 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +1.000000 -0.000000 0.000000 +0.987087 0.160182 0.000000 +0.987087 0.160182 0.000000 +0.987087 0.160182 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.011116 0.125442 0.992039 +0.024597 0.112430 0.993355 +0.000000 0.136135 0.990690 +0.000000 0.136135 0.990690 +0.000000 0.136135 0.990690 +0.000000 0.090945 0.995856 +0.000000 0.136135 0.990690 +0.000000 0.090945 0.995856 +0.000000 0.090945 0.995856 +0.011116 0.125442 0.992039 +0.000000 0.136135 0.990690 +0.000000 0.090945 0.995856 +0.962160 -0.000000 0.272486 +0.934506 0.171549 0.311880 +0.943771 0.131276 0.303418 +0.943771 0.131276 0.303418 +0.962160 0.000000 0.272486 +0.962160 -0.000000 0.272486 +0.067299 0.649221 -0.757617 +0.000000 0.686714 -0.726928 +0.000000 0.686714 -0.726928 +0.000000 0.686714 -0.726928 +0.128272 0.611135 -0.781063 +0.067299 0.649221 -0.757617 +0.163218 0.984625 -0.062245 +0.159865 0.985177 -0.062205 +0.000000 0.998433 -0.055963 +0.000000 0.998433 -0.055963 +0.000000 0.998433 -0.055964 +0.163218 0.984625 -0.062245 +0.999054 0.000000 -0.043479 +0.999027 0.000001 -0.044102 +0.986520 0.155080 -0.052242 +0.986520 0.155080 -0.052242 +0.985763 0.159892 -0.052024 +0.999054 0.000000 -0.043479 +0.999038 -0.000000 -0.043860 +0.999038 -0.000001 -0.043860 +0.999038 -0.000001 -0.043860 +0.999038 -0.000001 -0.043860 +0.999038 0.000000 -0.043860 +0.999038 -0.000000 -0.043860 +0.999054 0.000000 -0.043479 +0.999027 0.000000 -0.044102 +0.999027 0.000000 -0.044102 +0.999027 0.000000 -0.044102 +0.999054 -0.000000 -0.043483 +0.999054 0.000000 -0.043479 +0.691122 0.000000 -0.722738 +0.691122 0.000000 -0.722738 +0.653290 0.067038 -0.754134 +0.653290 0.067038 -0.754134 +0.613770 0.129389 -0.778810 +0.691122 0.000000 -0.722738 +0.682748 -0.000000 -0.730654 +0.682748 0.000000 -0.730654 +0.682742 -0.000001 -0.730659 +0.682742 -0.000001 -0.730659 +0.682742 -0.000001 -0.730659 +0.682748 -0.000000 -0.730654 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.216100 -0.970831 -0.103869 +0.216100 -0.970831 -0.103869 +0.216100 -0.970831 -0.103869 +0.217361 -0.970528 -0.104062 +0.217361 -0.970528 -0.104062 +0.217361 -0.970528 -0.104062 +0.207346 -0.926207 -0.314877 +0.207346 -0.926207 -0.314877 +0.207346 -0.926207 -0.314877 +0.205506 -0.932071 -0.298347 +0.205506 -0.932071 -0.298347 +0.205506 -0.932071 -0.298346 +0.211048 0.929400 -0.302779 +0.211048 0.929400 -0.302779 +0.211048 0.929400 -0.302779 +0.207481 0.926773 -0.313120 +0.207481 0.926773 -0.313120 +0.207481 0.926773 -0.313120 +0.217175 0.970455 -0.105127 +0.217175 0.970455 -0.105127 +0.217175 0.970455 -0.105127 +0.216090 0.970684 -0.105248 +0.216090 0.970684 -0.105248 +0.216090 0.970684 -0.105248 +0.194187 0.000000 -0.980965 +0.194187 0.000000 -0.980965 +0.194187 0.000000 -0.980965 +0.194186 -0.000000 -0.980965 +0.194186 -0.000000 -0.980965 +0.194186 -0.000000 -0.980965 +0.216066 -0.970705 -0.105102 +0.216066 -0.970705 -0.105102 +0.216066 -0.970705 -0.105102 +0.217172 -0.970440 -0.105272 +0.217172 -0.970440 -0.105272 +0.217172 -0.970440 -0.105272 +0.208395 -0.930879 -0.300060 +0.208395 -0.930879 -0.300060 +0.208395 -0.930879 -0.300060 +0.210116 -0.925295 -0.315722 +0.210116 -0.925295 -0.315722 +0.210116 -0.925295 -0.315722 +0.156370 0.985741 -0.062154 +0.000000 0.998433 -0.055963 +0.000000 0.998433 -0.055963 +0.000000 0.998433 -0.055963 +0.159865 0.985177 -0.062205 +0.156370 0.985741 -0.062154 +0.160185 0.987087 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.160185 0.987087 0.000000 +0.160185 0.987087 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.127993 0.011020 0.991714 +0.139053 -0.000000 0.990285 +0.139053 -0.000000 0.990285 +0.139053 -0.000000 0.990285 +0.113787 0.025124 0.993187 +0.127993 0.011020 0.991714 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.999067 0.000000 -0.043188 +0.999067 0.000000 -0.043189 +0.999054 0.000000 -0.043479 +0.999067 0.000000 -0.043188 +0.999054 0.000000 -0.043479 +0.999054 -0.000000 -0.043483 +0.999067 0.000000 -0.043188 +0.999054 -0.000000 -0.043483 +0.999054 0.000000 -0.043479 +0.999067 0.000000 -0.043188 +0.999054 0.000000 -0.043479 +0.985763 0.159892 -0.052024 +0.999067 0.000000 -0.043188 +0.985763 0.159892 -0.052024 +0.984968 0.164783 -0.051813 +0.194282 0.000000 -0.980946 +0.194282 0.000000 -0.980946 +0.194282 0.000000 -0.980946 +0.194281 -0.000000 -0.980946 +0.194281 -0.000000 -0.980946 +0.194281 -0.000000 -0.980946 +-0.000000 0.964133 0.265420 +-0.000000 0.964133 0.265419 +0.130684 0.945774 0.297376 +0.130684 0.945774 0.297376 +0.172667 0.936050 0.306588 +-0.000000 0.964133 0.265420 +0.130684 0.945774 0.297376 +-0.000000 0.964133 0.265419 +0.000000 0.964133 0.265419 +0.000000 0.964133 0.265419 +0.000000 0.964133 0.265419 +0.130684 0.945774 0.297376 +0.000000 0.964133 0.265420 +0.000000 0.964133 0.265419 +0.000000 0.964133 0.265419 +0.000000 0.964133 0.265419 +0.000000 0.964133 0.265420 +0.000000 0.964133 0.265420 +0.000000 0.090945 0.995856 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.090945 0.995856 +0.000000 0.090945 0.995856 +-0.974308 0.000000 -0.225220 +-0.974308 0.000000 -0.225220 +-0.974308 0.000000 -0.225220 +-0.974308 0.000000 -0.225220 +-0.974308 0.000000 -0.225220 +-0.974308 0.000000 -0.225220 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.705510 0.705201 -0.070341 +0.703604 0.707132 -0.070049 +0.984968 0.164783 -0.051813 +0.984968 0.164783 -0.051813 +0.985763 0.159892 -0.052024 +0.705510 0.705201 -0.070341 +0.707109 0.707105 0.000000 +0.707109 0.707105 0.000000 +0.160185 0.987087 0.000000 +0.160185 0.987087 0.000000 +0.160185 0.987087 0.000000 +0.707109 0.707105 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.068966 0.069266 0.995211 +0.069489 0.068754 0.995211 +0.127993 0.011020 0.991714 +0.127993 0.011020 0.991714 +0.113787 0.025124 0.993187 +0.068966 0.069266 0.995211 +0.656527 0.658833 0.367303 +0.658523 0.656830 0.367316 +0.172667 0.936050 0.306588 +0.172667 0.936050 0.306588 +0.130684 0.945774 0.297376 +0.656527 0.658833 0.367303 +0.393996 0.394840 -0.829981 +0.395300 0.393548 -0.829975 +0.067299 0.649221 -0.757617 +0.067299 0.649221 -0.757617 +0.128272 0.611135 -0.781063 +0.393996 0.394840 -0.829981 +0.707076 0.703599 -0.070651 +0.705510 0.705201 -0.070341 +0.985763 0.159892 -0.052024 +0.985763 0.159892 -0.052024 +0.986520 0.155080 -0.052242 +0.707076 0.703599 -0.070651 +0.159865 0.985177 -0.062205 +0.163218 0.984625 -0.062245 +0.703604 0.707132 -0.070049 +0.703604 0.707132 -0.070049 +0.705510 0.705201 -0.070341 +0.159865 0.985177 -0.062205 +0.987087 0.160182 0.000000 +0.987087 0.160182 0.000000 +0.707109 0.707105 0.000000 +0.707109 0.707105 0.000000 +0.707109 0.707105 0.000000 +0.987087 0.160182 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.024597 0.112430 0.993355 +0.011116 0.125442 0.992039 +0.069489 0.068754 0.995211 +0.069489 0.068754 0.995211 +0.068966 0.069266 0.995211 +0.024597 0.112430 0.993355 +0.943771 0.131276 0.303418 +0.934506 0.171549 0.311880 +0.658523 0.656830 0.367316 +0.658523 0.656830 0.367316 +0.656527 0.658833 0.367303 +0.943771 0.131276 0.303418 +0.613770 0.129389 -0.778810 +0.653290 0.067038 -0.754134 +0.395300 0.393548 -0.829975 +0.395300 0.393548 -0.829975 +0.393996 0.394840 -0.829981 +0.613770 0.129389 -0.778810 +0.156370 0.985741 -0.062154 +0.159865 0.985177 -0.062205 +0.705510 0.705201 -0.070341 +0.705510 0.705201 -0.070341 +0.707076 0.703599 -0.070651 +0.156370 0.985741 -0.062154 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +0.999042 0.000000 -0.043762 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.987088 -0.160179 0.000000 +0.987088 -0.160179 0.000000 +0.987088 -0.160179 0.000000 +1.000000 -0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.090945 0.995856 +0.000000 -0.136135 0.990690 +0.000000 -0.136135 0.990690 +0.000000 -0.090945 0.995856 +0.000000 -0.090945 0.995856 +0.000000 -0.136135 0.990690 +0.011116 -0.125442 0.992039 +0.000000 -0.090945 0.995856 +0.000000 -0.136135 0.990690 +0.011116 -0.125442 0.992039 +0.000000 -0.136135 0.990690 +0.024596 -0.112431 0.993355 +0.962160 -0.000000 0.272486 +0.962160 0.000000 0.272486 +0.943771 -0.131278 0.303418 +0.943771 -0.131278 0.303418 +0.934506 -0.171549 0.311879 +0.962160 -0.000000 0.272486 +0.067300 -0.649221 -0.757617 +0.128272 -0.611136 -0.781063 +0.000000 -0.686714 -0.726928 +0.000000 -0.686714 -0.726928 +0.000000 -0.686714 -0.726928 +0.067300 -0.649221 -0.757617 +0.163219 -0.984624 -0.062245 +0.000000 -0.998433 -0.055964 +-0.000000 -0.998433 -0.055963 +-0.000000 -0.998433 -0.055963 +0.159865 -0.985177 -0.062205 +0.163219 -0.984624 -0.062245 +0.999054 0.000000 -0.043479 +0.985762 -0.159895 -0.052024 +0.986519 -0.155083 -0.052243 +0.986519 -0.155083 -0.052243 +0.999027 0.000000 -0.044102 +0.999054 0.000000 -0.043479 +0.999038 0.000000 -0.043860 +0.999038 0.000000 -0.043860 +0.999038 0.000000 -0.043860 +0.999038 0.000000 -0.043860 +0.999038 0.000000 -0.043860 +0.999038 0.000000 -0.043860 +0.999054 -0.000000 -0.043479 +0.999054 0.000000 -0.043483 +0.999027 -0.000000 -0.044102 +0.999027 -0.000000 -0.044102 +0.999027 0.000000 -0.044102 +0.999054 -0.000000 -0.043479 +0.691125 -0.000000 -0.722735 +0.613769 -0.129389 -0.778811 +0.653289 -0.067036 -0.754135 +0.653289 -0.067036 -0.754135 +0.691125 -0.000000 -0.722735 +0.691125 -0.000000 -0.722735 +0.682748 0.000000 -0.730654 +0.682748 0.000000 -0.730654 +0.682748 0.000000 -0.730654 +0.682748 0.000000 -0.730654 +0.682748 0.000000 -0.730654 +0.682748 0.000000 -0.730654 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.691125 0.000000 -0.722735 +0.217362 0.970528 -0.104062 +0.217362 0.970528 -0.104062 +0.217362 0.970528 -0.104062 +0.216100 0.970831 -0.103869 +0.216100 0.970831 -0.103869 +0.216100 0.970831 -0.103869 +0.205507 0.932071 -0.298347 +0.205506 0.932071 -0.298347 +0.205507 0.932071 -0.298347 +0.207347 0.926207 -0.314876 +0.207347 0.926207 -0.314876 +0.207347 0.926207 -0.314876 +0.207481 -0.926773 -0.313119 +0.207481 -0.926773 -0.313119 +0.207481 -0.926773 -0.313119 +0.211048 -0.929400 -0.302779 +0.211048 -0.929400 -0.302779 +0.211048 -0.929400 -0.302779 +0.216091 -0.970684 -0.105248 +0.216090 -0.970684 -0.105248 +0.216090 -0.970684 -0.105248 +0.217175 -0.970455 -0.105127 +0.217175 -0.970455 -0.105127 +0.217175 -0.970455 -0.105127 +0.194186 0.000000 -0.980965 +0.194186 0.000000 -0.980965 +0.194186 0.000000 -0.980965 +0.194187 0.000000 -0.980965 +0.194187 0.000000 -0.980965 +0.194187 0.000000 -0.980965 +0.217172 0.970440 -0.105272 +0.217172 0.970440 -0.105272 +0.217171 0.970440 -0.105272 +0.216066 0.970705 -0.105103 +0.216066 0.970705 -0.105102 +0.216066 0.970705 -0.105103 +0.210116 0.925296 -0.315720 +0.210116 0.925296 -0.315720 +0.210116 0.925296 -0.315720 +0.208395 0.930880 -0.300057 +0.208395 0.930880 -0.300057 +0.208395 0.930880 -0.300057 +0.156370 -0.985741 -0.062154 +0.159865 -0.985177 -0.062205 +-0.000000 -0.998433 -0.055963 +-0.000000 -0.998433 -0.055963 +0.000000 -0.998433 -0.055963 +0.156370 -0.985741 -0.062154 +0.160183 -0.987087 0.000000 +0.160183 -0.987087 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.160183 -0.987087 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.127993 -0.011020 0.991714 +0.113788 -0.025124 0.993187 +0.139053 -0.000000 0.990285 +0.139053 -0.000000 0.990285 +0.139053 -0.000000 0.990285 +0.127993 -0.011020 0.991714 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.683002 0.000000 -0.730417 +0.999067 0.000000 -0.043188 +0.984968 -0.164786 -0.051813 +0.985762 -0.159895 -0.052024 +0.999067 0.000000 -0.043188 +0.985762 -0.159895 -0.052024 +0.999054 0.000000 -0.043479 +0.999067 0.000000 -0.043188 +0.999054 0.000000 -0.043479 +0.999054 0.000000 -0.043483 +0.999067 0.000000 -0.043188 +0.999054 0.000000 -0.043483 +0.999054 -0.000000 -0.043479 +0.999067 0.000000 -0.043188 +0.999054 -0.000000 -0.043479 +0.999067 0.000000 -0.043189 +0.194281 0.000000 -0.980946 +0.194281 0.000000 -0.980946 +0.194281 0.000000 -0.980946 +0.194282 0.000000 -0.980946 +0.194282 0.000000 -0.980946 +0.194282 0.000000 -0.980946 +-0.000000 -0.964133 0.265420 +0.172668 -0.936050 0.306589 +0.130685 -0.945774 0.297376 +0.130685 -0.945774 0.297376 +-0.000000 -0.964133 0.265419 +-0.000000 -0.964133 0.265420 +0.130685 -0.945774 0.297376 +0.000000 -0.964133 0.265419 +0.000000 -0.964133 0.265419 +0.000000 -0.964133 0.265419 +-0.000000 -0.964133 0.265419 +0.130685 -0.945774 0.297376 +0.000000 -0.964133 0.265420 +0.000000 -0.964133 0.265420 +0.000000 -0.964133 0.265419 +0.000000 -0.964133 0.265419 +0.000000 -0.964133 0.265419 +0.000000 -0.964133 0.265420 +0.000000 -0.090945 0.995856 +0.000000 -0.090945 0.995856 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.090945 0.995856 +-0.974308 0.000000 -0.225219 +-0.974308 0.000000 -0.225219 +-0.974308 0.000000 -0.225219 +-0.974308 0.000000 -0.225219 +-0.974308 0.000000 -0.225219 +-0.974308 0.000000 -0.225219 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.975766 0.000000 -0.218815 +0.705508 -0.705203 -0.070341 +0.985762 -0.159895 -0.052024 +0.984968 -0.164786 -0.051813 +0.984968 -0.164786 -0.051813 +0.703602 -0.707133 -0.070050 +0.705508 -0.705203 -0.070341 +0.707109 -0.707104 0.000000 +0.160183 -0.987087 0.000000 +0.160183 -0.987087 0.000000 +0.160183 -0.987087 0.000000 +0.707109 -0.707104 0.000000 +0.707109 -0.707104 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.068966 -0.069266 0.995212 +0.113788 -0.025124 0.993187 +0.127993 -0.011020 0.991714 +0.127993 -0.011020 0.991714 +0.069489 -0.068753 0.995211 +0.068966 -0.069266 0.995212 +0.656525 -0.658835 0.367303 +0.130685 -0.945774 0.297376 +0.172668 -0.936050 0.306589 +0.172668 -0.936050 0.306589 +0.658524 -0.656830 0.367316 +0.656525 -0.658835 0.367303 +0.393995 -0.394842 -0.829980 +0.128272 -0.611136 -0.781063 +0.067300 -0.649221 -0.757617 +0.067300 -0.649221 -0.757617 +0.395300 -0.393547 -0.829975 +0.393995 -0.394842 -0.829980 +0.707074 -0.703601 -0.070651 +0.986519 -0.155083 -0.052243 +0.985762 -0.159895 -0.052024 +0.985762 -0.159895 -0.052024 +0.705508 -0.705203 -0.070341 +0.707074 -0.703601 -0.070651 +0.159865 -0.985177 -0.062205 +0.705508 -0.705203 -0.070341 +0.703602 -0.707133 -0.070050 +0.703602 -0.707133 -0.070050 +0.163219 -0.984624 -0.062245 +0.159865 -0.985177 -0.062205 +0.987088 -0.160179 0.000000 +0.707109 -0.707104 0.000000 +0.707109 -0.707104 0.000000 +0.707109 -0.707104 0.000000 +0.987088 -0.160179 0.000000 +0.987088 -0.160179 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.024596 -0.112431 0.993355 +0.068966 -0.069266 0.995212 +0.069489 -0.068753 0.995211 +0.069489 -0.068753 0.995211 +0.011116 -0.125442 0.992039 +0.024596 -0.112431 0.993355 +0.943771 -0.131278 0.303418 +0.656525 -0.658835 0.367303 +0.658524 -0.656830 0.367316 +0.658524 -0.656830 0.367316 +0.934506 -0.171549 0.311879 +0.943771 -0.131278 0.303418 +0.613769 -0.129389 -0.778811 +0.393995 -0.394842 -0.829980 +0.395300 -0.393547 -0.829975 +0.395300 -0.393547 -0.829975 +0.653289 -0.067036 -0.754135 +0.613769 -0.129389 -0.778811 +0.156370 -0.985741 -0.062154 +0.707074 -0.703601 -0.070651 +0.705508 -0.705203 -0.070341 +0.705508 -0.705203 -0.070341 +0.159865 -0.985177 -0.062205 +0.156370 -0.985741 -0.062154 + - + - - 0.9182865 0.3786976 0.9182868 0.592559 0.9002661 0.5925588 0.9182865 0.3786976 0.9002661 0.5925588 0.892347 0.5849624 0.9182865 0.3786976 0.892347 0.5849624 0.8840656 0.3786978 0.9182864 0.3694939 0.8840656 0.3786978 0.883715 0.3694932 0.1566444 0.3412187 0.04588252 0.2990664 0.1566444 0.2990664 0.9571333 0.3386409 0.9571333 0.5525013 0.9403162 0.5525014 0.9571333 0.3386409 0.9403162 0.5525014 0.9322776 0.5449053 0.9571333 0.3386409 0.9322776 0.5449053 0.9207512 0.3386411 0.4605653 0.2528128 0.3739025 0.2140727 0.4605651 0.2140728 0.4280855 0.1316481 0.4634221 0.1205881 0.4634221 0.1316481 0.2725553 0.2528129 0.1882316 0.28561 0.1882315 0.252813 0.9201011 0.7424094 0.9450164 0.6148759 0.9450165 0.7424094 0.4326246 0.4419285 0.4756163 0.4326248 0.4756165 0.4419285 0.9002658 4.88286e-4 0.9182864 4.88286e-4 0.9182865 0.2143492 0.8923468 0.008084595 0.9002658 4.88286e-4 0.9182865 0.2143492 0.8923468 0.008084595 0.9182865 0.2143492 0.8840655 0.2143492 0.9403161 4.88303e-4 0.9571329 4.88287e-4 0.9571332 0.2143483 0.9322778 0.008084475 0.9403161 4.88303e-4 0.9571332 0.2143483 0.9322778 0.008084475 0.9571332 0.2143483 0.9207516 0.2143484 0.1792764 0.28561 0.05301839 0.2528129 0.1792763 0.2528129 0.9357133 0.8029695 0.924004 0.7990155 0.9201009 0.7871531 0.9450165 0.8029695 0.9357133 0.8029695 0.9201009 0.7871531 0.9201009 0.570132 0.924004 0.5582697 0.9357133 0.5543157 0.9201009 0.570132 0.9357133 0.5543157 0.9450165 0.5543156 4.88303e-4 0.3205851 0.04406833 0.3329567 4.88307e-4 0.3329567 0.2725553 0.2856099 0.2955789 0.252813 0.295579 0.2856099 0.1932691 0.907238 0.2051314 0.9111408 0.2090855 0.9228498 0.166933 0.9072378 0.1932691 0.907238 0.2090855 0.9228498 4.88282e-4 0.92285 0.004442393 0.9111411 0.01630425 0.907238 4.88282e-4 0.92285 0.01630425 0.907238 0.04264056 0.9072379 0.7285192 0.4506204 0.7285192 0.4958242 0.7187155 0.4958242 0.7105237 0.4326251 0.7285192 0.4506204 0.7187155 0.4958242 0.7105237 0.4326251 0.7251788 0.4359653 0.7285192 0.4506204 0.6264333 0.4419283 0.7187155 0.4958242 0.4326246 0.6419227 0.2725553 0.2528129 0.295579 0.2140727 0.2955789 0.252813 0.7187155 0.4958242 0.7187154 0.6065858 0.4326246 0.6419227 0.4326246 0.6419227 0.4756165 0.4419285 0.6264333 0.4419283 0.7187154 0.6065858 0.7103851 0.6419227 0.4326246 0.6419227 0.7311023 0.7581059 0.8586355 0.7581059 0.867367 0.7610166 0.867367 0.7610166 0.7223711 0.7610161 0.7311023 0.7581059 0.8701421 0.5603047 0.7426085 0.5603047 0.7338771 0.5573942 0.7338771 0.5573942 0.8788734 0.5573942 0.8701421 0.5603047 0.7190892 0.9275556 0.7190891 0.8400775 0.7219994 0.831346 0.7219994 0.831346 0.7219995 0.9362868 0.7190892 0.9275556 0.05752444 0.2874242 0.1450024 0.2874242 0.153734 0.2903351 0.153734 0.2903351 0.04879301 0.2903351 0.05752444 0.2874242 0.1491801 0.07562226 0.1416816 0.0840274 0.1360535 0.05899429 0.1427766 0.05496656 0.1459805 0.04982274 0.1526682 0.06678771 0.4496341 0.9265977 0.4541367 0.9357835 0.449634 0.9357835 0.5652344 0.9357835 0.5775492 0.9265977 0.5775492 0.9357835 0.4444977 0.9247831 0.456524 0.9155978 0.456524 0.9247831 0.3797456 0.9265977 0.4000297 0.9357835 0.3797456 0.9357835 0.04735714 0.01762789 0.05183398 0.06548821 0.04588836 0.07377058 0.1522934 0.02071493 0.1459805 0.04982274 0.1459411 0.02213335 0.07155132 0.05187094 0.0620597 0.053842 0.06636029 0.04771524 0.1491801 0.07562226 0.1526682 0.06678771 0.1583899 0.07515925 0.1583899 0.07515925 0.153132 0.08474558 0.1491801 0.07562226 0.06827884 0.006764054 0.1032041 4.88464e-4 0.1031009 0.006463944 0.1416816 0.0840274 0.153132 0.08474558 0.1293473 0.09187269 0.1276409 0.1844576 0.1010712 0.1931164 0.1010711 0.1844576 0.1293473 0.09187269 0.1282298 0.0844019 0.1416816 0.0840274 0.1416816 0.0840274 0.1491801 0.07562226 0.153132 0.08474558 0.1562597 0.1758696 0.1562597 0.1844575 0.1276409 0.1844576 0.1276409 0.1844576 0.149798 0.1758696 0.1562597 0.1758696 0.06446784 0.04335635 0.05961465 0.0207507 0.06499302 0.02227306 0.123577 0.06251293 0.1021029 0.08445197 0.1023678 0.06344956 0.06873148 0.05807965 0.06246048 0.08306509 0.05513036 0.07444918 0.05183398 0.06548821 0.05894839 0.04857367 0.0620597 0.053842 0.5234426 0.9357835 0.5279453 0.9265979 0.5279453 0.9357835 0.5056975 0.9155978 0.5411367 0.9247834 0.5056976 0.9247834 0.4887897 0.9357835 0.5234427 0.9265977 0.5234426 0.9357835 0.07352977 0.1931163 0.04588282 0.2023016 0.04588282 0.193116 0.3899179 0.9247831 0.4444976 0.9155978 0.4444977 0.9247831 0.5548712 0.9155978 0.5668978 0.9247831 0.5548712 0.9247831 0.05326932 0.01916384 0.05894839 0.04857367 0.05183398 0.06548821 0.1406086 0.0445531 0.1459411 0.02213335 0.1459805 0.04982274 0.05513036 0.07444918 0.05094891 0.0835188 0.04588836 0.07377058 0.04588836 0.07377058 0.05183398 0.06548821 0.05513036 0.07444918 0.06246048 0.08306509 0.07465165 0.0912249 0.05094891 0.0835188 0.04588252 0.1844576 0.07352977 0.1931163 0.04588282 0.193116 0.07465165 0.0912249 0.06246048 0.08306509 0.07595032 0.08376377 0.06246048 0.08306509 0.05094891 0.0835188 0.05513036 0.07444918 0.04588252 0.1758695 0.0523439 0.1758695 0.07450091 0.1844576 0.07450091 0.1844576 0.04588252 0.1844576 0.04588252 0.1758695 0.295579 0.205219 0.3186024 0.2140727 0.295579 0.2140727 0.3186025 0.3329197 0.2955789 0.3452492 0.295579 0.3329195 0.8842406 0.9410114 0.8623856 0.952134 0.8623856 0.9410116 0.9202634 0.223552 0.9571331 0.2327558 0.9201009 0.2327558 0.3186025 0.3205383 0.3649247 0.2944475 0.3649247 0.3205381 0.9571332 0.3202335 0.9201009 0.2327558 0.9571331 0.2327558 0.1577292 0.907238 0.1669332 0.9326535 0.1577293 0.9326534 0.04406833 0.3329567 4.8831e-4 0.3452001 4.88307e-4 0.3329567 0.04264074 0.9326536 4.88282e-4 0.92285 0.04264056 0.9072379 0.728519 0.6419227 0.7187154 0.6065858 0.7285189 0.6065858 0.05301839 0.2528129 0.1792763 0.2140728 0.1792763 0.2528129 0.04264056 0.9072379 0.05184453 0.9326536 0.04264074 0.9326536 4.88281e-4 0.28561 0.04406827 0.2944945 4.88297e-4 0.2944943 0.3649246 0.252813 0.3739026 0.28561 0.3649247 0.28561 0.3739026 0.28561 0.4605653 0.2528128 0.4605652 0.2856102 0.4695122 0.2528128 0.4605652 0.2856102 0.4605653 0.2528128 0.4605651 0.2140728 0.4695122 0.2528128 0.4605653 0.2528128 0.04406833 0.2051816 4.88345e-4 0.2140725 4.88343e-4 0.2051817 0.4695124 0.2944943 0.5055451 0.2856101 0.5055453 0.2944943 0.04588252 0.2990664 0.153734 0.2903351 0.1566444 0.2990664 0.5309278 0.9357835 0.5530718 0.9265979 0.5530717 0.9357835 0.558196 0.9357835 0.5652345 0.9265977 0.5652344 0.9357835 0.5279453 0.9357835 0.5309278 0.9265979 0.5309278 0.9357835 0.05789202 0.01086807 0.04735714 0.01762789 0.05387437 0.006297409 0.0458827 0.09480309 0.05506843 0.1021202 0.04588252 0.1021202 0.07595032 0.08376377 0.06873148 0.05807965 0.08117532 0.06195604 0.1562597 0.2023016 0.1286125 0.1931164 0.1562598 0.1931163 0.4123449 0.9265977 0.4193831 0.9357835 0.4123449 0.9357835 0.5668975 0.9155978 0.6214771 0.9247831 0.5668978 0.9247831 0.4000297 0.9265977 0.4123449 0.9357835 0.4000297 0.9357835 0.4702587 0.9247834 0.5056975 0.9155978 0.5056976 0.9247834 0.2955788 4.88289e-4 0.2725553 0.2052192 0.2725554 4.88297e-4 0.2955789 0.3205384 0.3186024 0.2944474 0.3186025 0.3205383 0.2955789 0.3452492 0.2725553 0.3329195 0.295579 0.3329195 0.3186025 0.3205383 0.295579 0.3329195 0.2955789 0.3205384 0.295579 0.3329195 0.2725553 0.3205384 0.2955789 0.3205384 0.9450165 0.5964685 0.9201009 0.570132 0.9450165 0.5543156 0.9060957 0.9521344 0.8842406 0.9410114 0.9060957 0.9410116 0.7914544 0.9521344 0.8623856 0.9410116 0.8623856 0.952134 0.4695124 0.3452002 0.5055454 0.3329566 0.5055454 0.3452002 0.8840655 0.2143492 0.9182864 0.2235528 0.883715 0.2235527 0.883715 0.2235527 0.9182868 0.2327569 0.8835983 0.2327569 0.9571332 0.3294374 0.9207512 0.3386411 0.9202635 0.3294375 0.9571332 0.3202335 0.9202635 0.3294375 0.9201007 0.3202334 0.2725553 0.3452491 0.1882315 0.3329193 0.2725553 0.3329195 0.9201009 0.7516131 0.9450165 0.7608169 0.9201009 0.7608169 0.1230109 0.05257523 0.08001965 0.04160183 0.1230109 0.04160183 0.9450164 0.6148759 0.9201011 0.6056721 0.9450164 0.6056721 0.9207516 0.2143484 0.9571331 0.2235522 0.9202634 0.223552 0.05184429 0.9072378 0.06104815 0.9326534 0.05184453 0.9326536 0.1485259 0.9326536 0.1577292 0.907238 0.1577293 0.9326534 0.04406827 0.2944945 4.88303e-4 0.3205851 4.88297e-4 0.2944943 4.88343e-4 0.2051817 0.04406833 6.73867e-4 0.04406833 0.2051816 0.3649246 0.252813 0.3739025 0.2140727 0.3739025 0.2528129 0.944592 0.8284353 0.730731 0.9391972 0.7307309 0.8284351 4.88342e-4 0.2528129 0.04406827 0.28561 4.88281e-4 0.28561 0.9450165 0.7516131 0.9201011 0.7424094 0.9450165 0.7424094 0.9182865 0.36029 0.8835983 0.2327569 0.9182868 0.2327569 0.7105237 0.4326251 0.6264333 0.4419283 0.6264333 0.4326247 0.4695122 0.3205853 0.5055454 0.3329566 0.4695124 0.3329566 0.04406833 0.2528129 0.05301839 0.2140728 0.05301839 0.2528129 0.1792763 0.2140728 0.1882315 0.252813 0.1792763 0.2528129 0.295579 0.2944474 0.3186024 0.2856103 0.3186024 0.2944474 0.295579 0.2856099 0.3186024 0.2528129 0.3186024 0.2856103 0.3649247 0.2944475 0.3186024 0.2856103 0.3649247 0.28561 0.3186024 0.2856103 0.3649246 0.252813 0.3649247 0.28561 0.2725553 0.2140727 0.1882316 0.2052192 0.2725553 0.2052192 0.295579 0.2140727 0.3186024 0.2528129 0.2955789 0.252813 0.1882315 0.252813 0.2725553 0.2140727 0.2725553 0.2528129 0.3186024 0.2052192 0.2955788 4.88289e-4 0.3186025 4.88513e-4 0.3649247 0.2052192 0.3186025 4.88513e-4 0.3649246 4.88281e-4 0.4695124 0.2140727 0.5055453 0.2528129 0.4695122 0.2528128 0.5055453 0.2140728 0.4695124 0.2051753 0.5055453 0.2051752 0.5055453 0.2051752 0.4695123 5.12323e-4 0.5055453 5.12315e-4 0.5055453 0.2528129 0.4695124 0.2856102 0.4695122 0.2528128 0.8817839 0.5486628 0.7309666 0.3348015 0.8817839 0.3348016 4.88342e-4 0.2528129 0.04406833 0.2140728 0.04406833 0.2528129 0.7309666 0.5486626 0.8788734 0.5573942 0.7338771 0.5573942 0.730731 0.9391972 0.7219994 0.831346 0.7307309 0.8284351 0.1434301 0.01716881 0.1377221 0.007961034 0.1479231 0.01234704 0.1526682 0.06678771 0.1360535 0.05899429 0.1427766 0.05496656 0.1369493 0.01433765 0.1031009 0.006463944 0.1377221 0.007961034 0.1522934 0.02071493 0.1434301 0.01716881 0.1479231 0.01234704 0.1360535 0.05899429 0.1282298 0.0844019 0.123577 0.06251293 0.4245075 0.9265977 0.4466516 0.9357835 0.4245074 0.9357835 0.1286125 0.2023019 0.1010712 0.1931164 0.1286125 0.1931164 0.1010712 0.1931164 0.07352977 0.2023016 0.07352977 0.1931163 0.4466516 0.9265977 0.449634 0.9357835 0.4466516 0.9357835 0.5411366 0.9155978 0.5548712 0.9247831 0.5411367 0.9247834 0.1282298 0.0844019 0.1020137 0.09187269 0.1021029 0.08445197 0.1023678 0.06344956 0.1221608 0.05621325 0.123577 0.06251293 0.139571 0.02124476 0.1369493 0.01433765 0.1434301 0.01716881 0.06751406 8.04474e-4 0.05789202 0.01086807 0.05387437 0.006297409 0.1334255 0.0527479 0.1427766 0.05496656 0.1360535 0.05899429 0.1359398 0.01979029 0.1029926 0.01307231 0.1369493 0.01433765 0.1032041 4.88464e-4 0.1377221 0.007961034 0.1031009 0.006463944 0.1459411 0.02213335 0.139571 0.02124476 0.1434301 0.01716881 0.08117532 0.06195604 0.07155132 0.05187094 0.08278739 0.05568909 0.1562597 0.1844575 0.1286125 0.1931164 0.1276409 0.1844576 0.08117532 0.06195604 0.1021029 0.08445197 0.07595032 0.08376377 0.1386654 0.04879873 0.1459805 0.04982274 0.1427766 0.05496656 0.06884676 0.01318633 0.1031009 0.006463944 0.1029926 0.01307231 0.4541368 0.9265977 0.4887897 0.9357835 0.4541367 0.9357835 0.1390759 0.1680715 0.1298903 0.1608373 0.1390759 0.1608373 0.149798 0.1758696 0.1562597 0.1666837 0.1562597 0.1758696 0.6214771 0.9247831 0.6316491 0.9155975 0.6316492 0.9247834 0.07595032 0.08376377 0.1020137 0.09187269 0.07465165 0.0912249 0.1023678 0.06344956 0.08278739 0.05568909 0.1024522 0.05688887 0.05961465 0.0207507 0.0660178 0.02002781 0.06499302 0.02227306 0.1386755 0.00206077 0.1479231 0.01234704 0.1377221 0.007961034 0.06636029 0.04771524 0.05894839 0.04857367 0.06446784 0.04335635 0.06967717 0.01867198 0.1029926 0.01307231 0.1029018 0.01896369 0.07450091 0.1844576 0.1010712 0.1931164 0.07352977 0.1931163 0.3649246 0.3329192 0.3186025 0.3452491 0.3186025 0.3329197 0.9182865 0.36029 0.883715 0.3694932 0.883598 0.36029 0.2725553 0.2944474 0.295579 0.2856099 0.295579 0.2944474 0.9060957 0.9410116 0.9425108 0.9521344 0.9060957 0.9521344 0.2725553 0.2944474 0.1882315 0.3205384 0.1882315 0.2944475 0.3186025 0.3329197 0.3649247 0.3205381 0.3649246 0.3329192 0.06104779 0.9072378 0.1485259 0.9326536 0.06104815 0.9326534 0.9201009 0.7871531 0.9450165 0.7608169 0.9450165 0.8029695 0.7194603 0.8119004 0.8702774 0.7697482 0.8702774 0.8119004 0.2090855 0.9228498 0.1669332 0.9326535 0.166933 0.9072378 0.1882315 0.252813 0.1792764 0.28561 0.1792763 0.2528129 0.05301833 0.28561 0.04406833 0.2528129 0.05301839 0.2528129 0.1882315 0.2944475 0.2725553 0.2856099 0.2725553 0.2944474 0.9450164 0.6056721 0.9201009 0.5964685 0.9450165 0.5964685 0.3649247 0.2052192 0.3186024 0.2140727 0.3186024 0.2052192 0.3186024 0.2140727 0.3649246 0.252813 0.3186024 0.2528129 0.2725553 0.2140727 0.295579 0.205219 0.295579 0.2140727 0.2725554 4.88297e-4 0.1882316 0.2052192 0.1882315 4.88337e-4 0.2725553 0.3329195 0.1882315 0.3205384 0.2725553 0.3205384 0.5055453 0.2944943 0.4695122 0.3205853 0.4695124 0.2944943 0.7194604 0.769748 0.867367 0.7610166 0.8702774 0.7697482 0.0622676 0.01583838 0.06827884 0.006764054 0.06884676 0.01318633 0.05183398 0.06548821 0.06873148 0.05807965 0.05513036 0.07444918 0.05326932 0.01916384 0.0622676 0.01583838 0.05961465 0.0207507 0.4193832 0.9265977 0.4245074 0.9357835 0.4193831 0.9357835 0.5530717 0.9357835 0.558196 0.9265977 0.558196 0.9357835 0.3899179 0.9247831 0.3797456 0.9155975 0.3899179 0.9155975 0.1479231 0.01234704 0.1582064 0.01933556 0.1522934 0.02071493 0.1390759 0.1680715 0.1298903 0.1753889 0.1252617 0.1680715 0.5775492 0.9357835 0.5978327 0.9265977 0.5978327 0.9357831 0.456524 0.9247831 0.4702587 0.9155978 0.4702587 0.9247834 0.05506855 0.08756864 0.0458827 0.09480309 0.04588252 0.08756864 0.0523439 0.1758695 0.04588282 0.1666837 0.05234396 0.1666837 0.0660178 0.02002781 0.06884676 0.01318633 0.06967717 0.01867198 0.1334255 0.0527479 0.123577 0.06251293 0.1221608 0.05621325 0.2725553 0.3205384 0.295579 0.2944474 0.2955789 0.3205384 0.4756165 0.4419285 0.4326246 0.6419227 0.4326246 0.4419285 0.1582064 0.01933556 0.1526682 0.06678771 0.1522934 0.02071493 1.918286 0.3786976 1.900266 0.5925588 1.918287 0.592559 1.918286 0.3786976 1.892347 0.5849624 1.900266 0.5925588 1.918286 0.3786976 1.884066 0.3786978 1.892347 0.5849624 1.918286 0.3694939 1.884066 0.3786978 1.918286 0.3786976 1.045883 0.2990664 1.156644 0.3412187 1.156644 0.2990664 1.957133 0.3386409 1.940316 0.5525014 1.957133 0.5525013 1.957133 0.3386409 1.932278 0.5449053 1.940316 0.5525014 1.957133 0.3386409 1.920751 0.3386411 1.932278 0.5449053 1.460565 0.2528128 1.373903 0.2140727 1.373903 0.2528129 1.463422 0.1205881 1.428085 0.1316481 1.463422 0.1316481 1.272555 0.2528129 1.188232 0.28561 1.272555 0.2856099 1.945016 0.6148759 1.920101 0.7424094 1.945016 0.7424094 1.475616 0.4326248 1.432625 0.4419285 1.475616 0.4419285 1.900266 4.88286e-4 1.918287 0.2143492 1.918286 4.88286e-4 1.892347 0.008084595 1.918287 0.2143492 1.900266 4.88286e-4 1.892347 0.008084595 1.884065 0.2143492 1.918287 0.2143492 1.940316 4.88303e-4 1.957133 0.2143483 1.957133 4.88287e-4 1.932278 0.008084475 1.957133 0.2143483 1.940316 4.88303e-4 1.932278 0.008084475 1.920752 0.2143484 1.957133 0.2143483 1.179276 0.28561 1.053018 0.2528129 1.053018 0.28561 1.935713 0.8029695 1.920101 0.7871531 1.924004 0.7990155 1.945016 0.8029695 1.920101 0.7871531 1.935713 0.8029695 1.920101 0.570132 1.935713 0.5543157 1.924004 0.5582697 1.920101 0.570132 1.945016 0.5543156 1.935713 0.5543157 1.044068 0.3329567 1.000488 0.3205851 1.000488 0.3329567 1.295579 0.252813 1.272555 0.2856099 1.295579 0.2856099 1.193269 0.907238 1.209085 0.9228498 1.205131 0.9111408 1.166933 0.9072378 1.209085 0.9228498 1.193269 0.907238 1.000488 0.92285 1.016304 0.907238 1.004442 0.9111411 1.000488 0.92285 1.042641 0.9072379 1.016304 0.907238 1.728519 0.4506204 1.718715 0.4958242 1.728519 0.4958242 1.710524 0.4326251 1.718715 0.4958242 1.728519 0.4506204 1.710524 0.4326251 1.728519 0.4506204 1.725179 0.4359653 1.626433 0.4419283 1.432625 0.6419227 1.718715 0.4958242 1.272555 0.2528129 1.295579 0.2140727 1.272555 0.2140727 1.718715 0.4958242 1.432625 0.6419227 1.718715 0.6065858 1.432625 0.6419227 1.626433 0.4419283 1.475616 0.4419285 1.718715 0.6065858 1.432625 0.6419227 1.710385 0.6419227 1.731102 0.7581059 1.867367 0.7610166 1.858635 0.7581059 1.867367 0.7610166 1.731102 0.7581059 1.722371 0.7610161 1.870142 0.5603047 1.733877 0.5573942 1.742609 0.5603047 1.733877 0.5573942 1.870142 0.5603047 1.878873 0.5573942 1.719089 0.9275556 1.721999 0.831346 1.719089 0.8400775 1.721999 0.831346 1.719089 0.9275556 1.721999 0.9362868 1.057524 0.2874242 1.153734 0.2903351 1.145002 0.2874242 1.153734 0.2903351 1.057524 0.2874242 1.048793 0.2903351 1.14918 0.07562226 1.136054 0.05899429 1.141682 0.0840274 1.142777 0.05496656 1.152668 0.06678771 1.14598 0.04982274 1.454137 0.9357835 1.449634 0.9265977 1.449634 0.9357835 1.577549 0.9265977 1.565234 0.9357835 1.577549 0.9357835 1.456524 0.9155978 1.444498 0.9247831 1.456524 0.9247831 1.40003 0.9357835 1.379746 0.9265977 1.379746 0.9357835 1.047357 0.01762789 1.051834 0.06548821 1.053269 0.01916384 1.152293 0.02071493 1.14598 0.04982274 1.152668 0.06678771 1.071551 0.05187094 1.06206 0.053842 1.068732 0.05807965 1.14918 0.07562226 1.15839 0.07515925 1.152668 0.06678771 1.15839 0.07515925 1.14918 0.07562226 1.153132 0.08474558 1.103204 4.88464e-4 1.068279 0.006764054 1.103101 0.006463944 1.141682 0.0840274 1.129347 0.09187269 1.153132 0.08474558 1.127641 0.1844576 1.101071 0.1931164 1.128612 0.1931164 1.129347 0.09187269 1.141682 0.0840274 1.12823 0.0844019 1.141682 0.0840274 1.153132 0.08474558 1.14918 0.07562226 1.15626 0.1758696 1.127641 0.1844576 1.15626 0.1844575 1.127641 0.1844576 1.15626 0.1758696 1.149798 0.1758696 1.064468 0.04335635 1.059615 0.0207507 1.058948 0.04857367 1.123577 0.06251293 1.102103 0.08445197 1.12823 0.0844019 1.068732 0.05807965 1.05513 0.07444918 1.062461 0.08306509 1.051834 0.06548821 1.06206 0.053842 1.058948 0.04857367 1.527945 0.9265979 1.523443 0.9357835 1.527945 0.9357835 1.541137 0.9247834 1.505697 0.9155978 1.505697 0.9247834 1.523443 0.9265977 1.48879 0.9357835 1.523443 0.9357835 1.045883 0.2023016 1.07353 0.1931163 1.045883 0.193116 1.444498 0.9155978 1.389918 0.9247831 1.444498 0.9247831 1.566898 0.9247831 1.554871 0.9155978 1.554871 0.9247831 1.053269 0.01916384 1.058948 0.04857367 1.059615 0.0207507 1.140609 0.0445531 1.145941 0.02213335 1.14054 0.0235123 1.05513 0.07444918 1.045888 0.07377058 1.050949 0.0835188 1.045888 0.07377058 1.05513 0.07444918 1.051834 0.06548821 1.062461 0.08306509 1.050949 0.0835188 1.074652 0.0912249 1.045883 0.1844576 1.07353 0.1931163 1.074501 0.1844576 1.074652 0.0912249 1.07595 0.08376377 1.062461 0.08306509 1.062461 0.08306509 1.05513 0.07444918 1.050949 0.0835188 1.045883 0.1758695 1.074501 0.1844576 1.052344 0.1758695 1.074501 0.1844576 1.045883 0.1758695 1.045883 0.1844576 1.295579 0.205219 1.318602 0.2140727 1.318602 0.2052192 1.318602 0.3329197 1.295579 0.3452492 1.318602 0.3452491 1.884241 0.9410114 1.862386 0.952134 1.884241 0.9521344 1.920263 0.223552 1.957133 0.2327558 1.957133 0.2235522 1.364925 0.2944475 1.318602 0.3205383 1.364925 0.3205381 1.920101 0.2327558 1.957133 0.3202335 1.957133 0.2327558 1.157729 0.907238 1.166933 0.9326535 1.166933 0.9072378 1.000488 0.3452001 1.044068 0.3329567 1.000488 0.3329567 1.042641 0.9326536 1.000488 0.92285 1.000488 0.9326536 1.728519 0.6419227 1.718715 0.6065858 1.710385 0.6419227 1.053018 0.2528129 1.179276 0.2140728 1.053018 0.2140728 1.051845 0.9326536 1.042641 0.9072379 1.042641 0.9326536 1.000488 0.28561 1.044068 0.2944945 1.044068 0.28561 1.373903 0.28561 1.364925 0.252813 1.364925 0.28561 1.373903 0.28561 1.460565 0.2528128 1.373903 0.2528129 1.469512 0.2528128 1.460565 0.2856102 1.469512 0.2856102 1.460565 0.2140728 1.469512 0.2528128 1.469512 0.2140727 1.000488 0.2140725 1.044068 0.2051816 1.000488 0.2051817 1.505545 0.2856101 1.469512 0.2944943 1.505545 0.2944943 1.156644 0.2990664 1.048793 0.2903351 1.045883 0.2990664 1.553072 0.9265979 1.530928 0.9357835 1.553072 0.9357835 1.565234 0.9265977 1.558196 0.9357835 1.565234 0.9357835 1.530928 0.9265979 1.527945 0.9357835 1.530928 0.9357835 1.057892 0.01086807 1.047357 0.01762789 1.053269 0.01916384 1.045883 0.09480309 1.055068 0.1021202 1.059697 0.09480309 1.068732 0.05807965 1.07595 0.08376377 1.081175 0.06195604 1.128612 0.1931164 1.15626 0.2023016 1.15626 0.1931163 1.419383 0.9357835 1.412345 0.9265977 1.412345 0.9357835 1.621477 0.9247831 1.566897 0.9155978 1.566898 0.9247831 1.412345 0.9357835 1.40003 0.9265977 1.40003 0.9357835 1.505697 0.9155978 1.470259 0.9247834 1.505697 0.9247834 1.295579 4.88289e-4 1.272555 0.2052192 1.295579 0.205219 1.318602 0.2944474 1.295579 0.3205384 1.318602 0.3205383 1.272555 0.3329195 1.295579 0.3452492 1.295579 0.3329195 1.318602 0.3205383 1.295579 0.3329195 1.318602 0.3329197 1.272555 0.3205384 1.295579 0.3329195 1.295579 0.3205384 1.945016 0.5964685 1.920101 0.570132 1.920101 0.5964685 1.906096 0.9521344 1.884241 0.9410114 1.884241 0.9521344 1.791454 0.9521344 1.862386 0.9410116 1.791454 0.9410114 1.469512 0.3452002 1.505545 0.3329566 1.469512 0.3329566 1.884065 0.2143492 1.918286 0.2235528 1.918287 0.2143492 1.883715 0.2235527 1.918287 0.2327569 1.918286 0.2235528 1.957133 0.3294374 1.920751 0.3386411 1.957133 0.3386409 1.957133 0.3202335 1.920264 0.3294375 1.957133 0.3294374 1.272555 0.3452491 1.188232 0.3329193 1.188232 0.3452492 1.945016 0.7608169 1.920101 0.7516131 1.920101 0.7608169 1.08002 0.04160183 1.123011 0.05257523 1.123011 0.04160183 1.945016 0.6148759 1.920101 0.6056721 1.920101 0.6148759 1.920752 0.2143484 1.957133 0.2235522 1.957133 0.2143483 1.061048 0.9326534 1.051844 0.9072378 1.051845 0.9326536 1.148526 0.9326536 1.157729 0.907238 1.148526 0.9072379 1.000488 0.3205851 1.044068 0.2944945 1.000488 0.2944943 1.044068 6.73867e-4 1.000488 0.2051817 1.044068 0.2051816 1.364925 0.252813 1.373903 0.2140727 1.364925 0.2140727 1.730731 0.9391972 1.944592 0.8284353 1.730731 0.8284351 1.000488 0.2528129 1.044068 0.28561 1.044068 0.2528129 1.945016 0.7516131 1.920101 0.7424094 1.920101 0.7516131 1.883598 0.2327569 1.918286 0.36029 1.918287 0.2327569 1.710524 0.4326251 1.626433 0.4419283 1.718715 0.4958242 1.505545 0.3329566 1.469512 0.3205853 1.469512 0.3329566 1.044068 0.2528129 1.053018 0.2140728 1.044068 0.2140728 1.179276 0.2140728 1.188231 0.252813 1.188232 0.2140728 1.318602 0.2856103 1.295579 0.2944474 1.318602 0.2944474 1.318602 0.2528129 1.295579 0.2856099 1.318602 0.2856103 1.364925 0.2944475 1.318602 0.2856103 1.318602 0.2944474 1.364925 0.252813 1.318602 0.2856103 1.364925 0.28561 1.272555 0.2140727 1.188232 0.2052192 1.188232 0.2140728 1.295579 0.2140727 1.318602 0.2528129 1.318602 0.2140727 1.272555 0.2140727 1.188231 0.252813 1.272555 0.2528129 1.318602 0.2052192 1.295579 4.88289e-4 1.295579 0.205219 1.364925 0.2052192 1.318603 4.88513e-4 1.318602 0.2052192 1.505545 0.2528129 1.469512 0.2140727 1.469512 0.2528128 1.505545 0.2140728 1.469512 0.2051753 1.469512 0.2140727 1.469512 5.12323e-4 1.505545 0.2051752 1.505545 5.12315e-4 1.505545 0.2528129 1.469512 0.2856102 1.505545 0.2856101 1.730967 0.3348015 1.881784 0.5486628 1.881784 0.3348016 1.000488 0.2528129 1.044068 0.2140728 1.000488 0.2140725 1.730967 0.5486626 1.878873 0.5573942 1.881784 0.5486628 1.721999 0.831346 1.730731 0.9391972 1.730731 0.8284351 1.14343 0.01716881 1.137722 0.007961034 1.136949 0.01433765 1.152668 0.06678771 1.136054 0.05899429 1.14918 0.07562226 1.136949 0.01433765 1.103101 0.006463944 1.102993 0.01307231 1.152293 0.02071493 1.14343 0.01716881 1.145941 0.02213335 1.12823 0.0844019 1.136054 0.05899429 1.123577 0.06251293 1.446652 0.9357835 1.424507 0.9265977 1.424507 0.9357835 1.101071 0.1931164 1.128612 0.2023019 1.128612 0.1931164 1.07353 0.2023016 1.101071 0.1931164 1.07353 0.1931163 1.449634 0.9357835 1.446652 0.9265977 1.446652 0.9357835 1.554871 0.9247831 1.541136 0.9155978 1.541137 0.9247834 1.12823 0.0844019 1.102014 0.09187269 1.129347 0.09187269 1.102368 0.06344956 1.122161 0.05621325 1.102452 0.05688887 1.139571 0.02124476 1.136949 0.01433765 1.13594 0.01979029 1.067514 8.04474e-4 1.057892 0.01086807 1.068279 0.006764054 1.133425 0.0527479 1.142777 0.05496656 1.138665 0.04879873 1.13594 0.01979029 1.102993 0.01307231 1.102902 0.01896369 1.137722 0.007961034 1.103204 4.88464e-4 1.103101 0.006463944 1.145941 0.02213335 1.139571 0.02124476 1.14054 0.0235123 1.071551 0.05187094 1.081175 0.06195604 1.082787 0.05568909 1.15626 0.1844575 1.128612 0.1931164 1.15626 0.1931163 1.081175 0.06195604 1.102103 0.08445197 1.102368 0.06344956 1.138665 0.04879873 1.14598 0.04982274 1.140609 0.0445531 1.068847 0.01318633 1.103101 0.006463944 1.068279 0.006764054 1.48879 0.9357835 1.454137 0.9265977 1.454137 0.9357835 1.12989 0.1608373 1.139076 0.1680715 1.139076 0.1608373 1.149798 0.1758696 1.15626 0.1666837 1.149798 0.1666839 1.621477 0.9247831 1.631649 0.9155975 1.621477 0.9155975 1.07595 0.08376377 1.102014 0.09187269 1.102103 0.08445197 1.102368 0.06344956 1.082787 0.05568909 1.081175 0.06195604 1.059615 0.0207507 1.066018 0.02002781 1.062268 0.01583838 1.138676 0.00206077 1.147923 0.01234704 1.152043 0.007921338 1.06636 0.04771524 1.058948 0.04857367 1.06206 0.053842 1.069677 0.01867198 1.102993 0.01307231 1.068847 0.01318633 1.074501 0.1844576 1.101071 0.1931164 1.101071 0.1844576 1.364925 0.3329192 1.318602 0.3452491 1.364925 0.3452492 1.918286 0.36029 1.883715 0.3694932 1.918286 0.3694939 1.295579 0.2856099 1.272555 0.2944474 1.295579 0.2944474 1.906096 0.9410116 1.942511 0.9521344 1.942511 0.9410114 1.188232 0.3205384 1.272555 0.2944474 1.188232 0.2944475 1.318602 0.3329197 1.364925 0.3205381 1.318602 0.3205383 1.061048 0.9072378 1.148526 0.9326536 1.148526 0.9072379 1.920101 0.7871531 1.945016 0.7608169 1.920101 0.7608169 1.870277 0.7697482 1.71946 0.8119004 1.870277 0.8119004 1.209085 0.9228498 1.166933 0.9326535 1.209086 0.9326535 1.188231 0.252813 1.179276 0.28561 1.188232 0.28561 1.053018 0.28561 1.044068 0.2528129 1.044068 0.28561 1.272555 0.2856099 1.188232 0.2944475 1.272555 0.2944474 1.945016 0.6056721 1.920101 0.5964685 1.920101 0.6056721 1.364925 0.2052192 1.318602 0.2140727 1.364925 0.2140727 1.318602 0.2140727 1.364925 0.252813 1.364925 0.2140727 1.272555 0.2140727 1.295579 0.205219 1.272555 0.2052192 1.272555 4.88297e-4 1.188232 0.2052192 1.272555 0.2052192 1.272555 0.3329195 1.188232 0.3205384 1.188232 0.3329193 1.469512 0.3205853 1.505545 0.2944943 1.469512 0.2944943 1.867367 0.7610166 1.71946 0.769748 1.870277 0.7697482 1.062268 0.01583838 1.068279 0.006764054 1.057892 0.01086807 1.068732 0.05807965 1.051834 0.06548821 1.05513 0.07444918 1.053269 0.01916384 1.062268 0.01583838 1.057892 0.01086807 1.424507 0.9357835 1.419383 0.9265977 1.419383 0.9357835 1.558196 0.9265977 1.553072 0.9357835 1.558196 0.9357835 1.389918 0.9247831 1.379746 0.9155975 1.379746 0.9247834 1.147923 0.01234704 1.158206 0.01933556 1.152043 0.007921338 1.139076 0.1680715 1.12989 0.1753889 1.139076 0.1753889 1.597833 0.9265977 1.577549 0.9357835 1.597833 0.9357831 1.470259 0.9155978 1.456524 0.9247831 1.470259 0.9247834 1.045883 0.09480309 1.055069 0.08756864 1.045883 0.08756864 1.052344 0.1758695 1.045883 0.1666837 1.045883 0.1758695 1.066018 0.02002781 1.068847 0.01318633 1.062268 0.01583838 1.123577 0.06251293 1.133425 0.0527479 1.122161 0.05621325 1.295579 0.2944474 1.272555 0.3205384 1.295579 0.3205384 1.475616 0.4419285 1.432625 0.4419285 1.432625 0.6419227 1.158206 0.01933556 1.152668 0.06678771 1.15839 0.07515925 1.918286 0.3786976 1.900266 0.5925588 1.918287 0.592559 1.918286 0.3786976 1.892347 0.5849624 1.900266 0.5925588 1.918286 0.3786976 1.884066 0.3786978 1.892347 0.5849624 1.918286 0.3694939 1.884066 0.3786978 1.918286 0.3786976 1.045883 0.2990664 1.156644 0.3412187 1.156644 0.2990664 1.957133 0.3386409 1.940316 0.5525014 1.957133 0.5525013 1.957133 0.3386409 1.932278 0.5449053 1.940316 0.5525014 1.957133 0.3386409 1.920751 0.3386411 1.932278 0.5449053 1.460565 0.2528128 1.373903 0.2140727 1.373903 0.2528129 1.463422 0.1205881 1.428085 0.1316481 1.463422 0.1316481 1.272555 0.2528129 1.188232 0.28561 1.272555 0.2856099 1.945016 0.6148759 1.920101 0.7424094 1.945016 0.7424094 1.475616 0.4326248 1.432625 0.4419285 1.475616 0.4419285 1.900266 4.88286e-4 1.918287 0.2143492 1.918286 4.88286e-4 1.892347 0.008084595 1.918287 0.2143492 1.900266 4.88286e-4 1.892347 0.008084595 1.884065 0.2143492 1.918287 0.2143492 1.940316 4.88303e-4 1.957133 0.2143483 1.957133 4.88287e-4 1.932278 0.008084475 1.957133 0.2143483 1.940316 4.88303e-4 1.932278 0.008084475 1.920752 0.2143484 1.957133 0.2143483 1.179276 0.28561 1.053018 0.2528129 1.053018 0.28561 1.935713 0.8029695 1.920101 0.7871531 1.924004 0.7990155 1.945016 0.8029695 1.920101 0.7871531 1.935713 0.8029695 1.920101 0.570132 1.935713 0.5543157 1.924004 0.5582697 1.920101 0.570132 1.945016 0.5543156 1.935713 0.5543157 1.044068 0.3329567 1.000488 0.3205851 1.000488 0.3329567 1.295579 0.252813 1.272555 0.2856099 1.295579 0.2856099 1.193269 0.907238 1.209085 0.9228498 1.205131 0.9111408 1.166933 0.9072378 1.209085 0.9228498 1.193269 0.907238 1.000488 0.92285 1.016304 0.907238 1.004442 0.9111411 1.000488 0.92285 1.042641 0.9072379 1.016304 0.907238 1.728519 0.4506204 1.718715 0.4958242 1.728519 0.4958242 1.710524 0.4326251 1.718715 0.4958242 1.728519 0.4506204 1.710524 0.4326251 1.728519 0.4506204 1.725179 0.4359653 1.626433 0.4419283 1.432625 0.6419227 1.718715 0.4958242 1.272555 0.2528129 1.295579 0.2140727 1.272555 0.2140727 1.718715 0.4958242 1.432625 0.6419227 1.718715 0.6065858 1.432625 0.6419227 1.626433 0.4419283 1.475616 0.4419285 1.718715 0.6065858 1.432625 0.6419227 1.710385 0.6419227 1.731102 0.7581059 1.867367 0.7610166 1.858635 0.7581059 1.867367 0.7610166 1.731102 0.7581059 1.722371 0.7610161 1.870142 0.5603047 1.733877 0.5573942 1.742609 0.5603047 1.733877 0.5573942 1.870142 0.5603047 1.878873 0.5573942 1.719089 0.9275556 1.721999 0.831346 1.719089 0.8400775 1.721999 0.831346 1.719089 0.9275556 1.721999 0.9362868 1.057524 0.2874242 1.153734 0.2903351 1.145002 0.2874242 1.153734 0.2903351 1.057524 0.2874242 1.048793 0.2903351 1.14918 0.07562226 1.136054 0.05899429 1.141682 0.0840274 1.142777 0.05496656 1.152668 0.06678771 1.14598 0.04982274 1.454137 0.9357835 1.449634 0.9265977 1.449634 0.9357835 1.577549 0.9265977 1.565234 0.9357835 1.577549 0.9357835 1.456524 0.9155978 1.444498 0.9247831 1.456524 0.9247831 1.40003 0.9357835 1.379746 0.9265977 1.379746 0.9357835 1.047357 0.01762789 1.051834 0.06548821 1.053269 0.01916384 1.152293 0.02071493 1.14598 0.04982274 1.152668 0.06678771 1.071551 0.05187094 1.06206 0.053842 1.068732 0.05807965 1.14918 0.07562226 1.15839 0.07515925 1.152668 0.06678771 1.15839 0.07515925 1.14918 0.07562226 1.153132 0.08474558 1.103204 4.88464e-4 1.068279 0.006764054 1.103101 0.006463944 1.141682 0.0840274 1.129347 0.09187269 1.153132 0.08474558 1.127641 0.1844576 1.101071 0.1931164 1.128612 0.1931164 1.129347 0.09187269 1.141682 0.0840274 1.12823 0.0844019 1.141682 0.0840274 1.153132 0.08474558 1.14918 0.07562226 1.15626 0.1758696 1.127641 0.1844576 1.15626 0.1844575 1.127641 0.1844576 1.15626 0.1758696 1.149798 0.1758696 1.064468 0.04335635 1.059615 0.0207507 1.058948 0.04857367 1.123577 0.06251293 1.102103 0.08445197 1.12823 0.0844019 1.068732 0.05807965 1.05513 0.07444918 1.062461 0.08306509 1.051834 0.06548821 1.06206 0.053842 1.058948 0.04857367 1.527945 0.9265979 1.523443 0.9357835 1.527945 0.9357835 1.541137 0.9247834 1.505697 0.9155978 1.505697 0.9247834 1.523443 0.9265977 1.48879 0.9357835 1.523443 0.9357835 1.045883 0.2023016 1.07353 0.1931163 1.045883 0.193116 1.444498 0.9155978 1.389918 0.9247831 1.444498 0.9247831 1.566898 0.9247831 1.554871 0.9155978 1.554871 0.9247831 1.053269 0.01916384 1.058948 0.04857367 1.059615 0.0207507 1.140609 0.0445531 1.145941 0.02213335 1.14054 0.0235123 1.05513 0.07444918 1.045888 0.07377058 1.050949 0.0835188 1.045888 0.07377058 1.05513 0.07444918 1.051834 0.06548821 1.062461 0.08306509 1.050949 0.0835188 1.074652 0.0912249 1.045883 0.1844576 1.07353 0.1931163 1.074501 0.1844576 1.074652 0.0912249 1.07595 0.08376377 1.062461 0.08306509 1.062461 0.08306509 1.05513 0.07444918 1.050949 0.0835188 1.045883 0.1758695 1.074501 0.1844576 1.052344 0.1758695 1.074501 0.1844576 1.045883 0.1758695 1.045883 0.1844576 1.295579 0.205219 1.318602 0.2140727 1.318602 0.2052192 1.318602 0.3329197 1.295579 0.3452492 1.318602 0.3452491 1.884241 0.9410114 1.862386 0.952134 1.884241 0.9521344 1.920263 0.223552 1.957133 0.2327558 1.957133 0.2235522 1.364925 0.2944475 1.318602 0.3205383 1.364925 0.3205381 1.920101 0.2327558 1.957133 0.3202335 1.957133 0.2327558 1.157729 0.907238 1.166933 0.9326535 1.166933 0.9072378 1.000488 0.3452001 1.044068 0.3329567 1.000488 0.3329567 1.042641 0.9326536 1.000488 0.92285 1.000488 0.9326536 1.728519 0.6419227 1.718715 0.6065858 1.710385 0.6419227 1.053018 0.2528129 1.179276 0.2140728 1.053018 0.2140728 1.051845 0.9326536 1.042641 0.9072379 1.042641 0.9326536 1.000488 0.28561 1.044068 0.2944945 1.044068 0.28561 1.373903 0.28561 1.364925 0.252813 1.364925 0.28561 1.373903 0.28561 1.460565 0.2528128 1.373903 0.2528129 1.469512 0.2528128 1.460565 0.2856102 1.469512 0.2856102 1.460565 0.2140728 1.469512 0.2528128 1.469512 0.2140727 1.000488 0.2140725 1.044068 0.2051816 1.000488 0.2051817 1.505545 0.2856101 1.469512 0.2944943 1.505545 0.2944943 1.153734 0.2903351 1.045883 0.2990664 1.156644 0.2990664 1.553072 0.9265979 1.530928 0.9357835 1.553072 0.9357835 1.565234 0.9265977 1.558196 0.9357835 1.565234 0.9357835 1.530928 0.9265979 1.527945 0.9357835 1.530928 0.9357835 1.057892 0.01086807 1.047357 0.01762789 1.053269 0.01916384 1.045883 0.09480309 1.055068 0.1021202 1.059697 0.09480309 1.068732 0.05807965 1.07595 0.08376377 1.081175 0.06195604 1.128612 0.1931164 1.15626 0.2023016 1.15626 0.1931163 1.419383 0.9357835 1.412345 0.9265977 1.412345 0.9357835 1.621477 0.9247831 1.566897 0.9155978 1.566898 0.9247831 1.412345 0.9357835 1.40003 0.9265977 1.40003 0.9357835 1.505697 0.9155978 1.470259 0.9247834 1.505697 0.9247834 1.295579 4.88289e-4 1.272555 0.2052192 1.295579 0.205219 1.318602 0.2944474 1.295579 0.3205384 1.318602 0.3205383 1.272555 0.3329195 1.295579 0.3452492 1.295579 0.3329195 1.318602 0.3205383 1.295579 0.3329195 1.318602 0.3329197 1.272555 0.3205384 1.295579 0.3329195 1.295579 0.3205384 1.945016 0.5964685 1.920101 0.570132 1.920101 0.5964685 1.906096 0.9521344 1.884241 0.9410114 1.884241 0.9521344 1.791454 0.9521344 1.862386 0.9410116 1.791454 0.9410114 1.469512 0.3452002 1.505545 0.3329566 1.469512 0.3329566 1.884065 0.2143492 1.918286 0.2235528 1.918287 0.2143492 1.883715 0.2235527 1.918287 0.2327569 1.918286 0.2235528 1.957133 0.3294374 1.920751 0.3386411 1.957133 0.3386409 1.957133 0.3202335 1.920264 0.3294375 1.957133 0.3294374 1.272555 0.3452491 1.188232 0.3329193 1.188232 0.3452492 1.945016 0.7608169 1.920101 0.7516131 1.920101 0.7608169 1.08002 0.04160183 1.123011 0.05257523 1.123011 0.04160183 1.945016 0.6148759 1.920101 0.6056721 1.920101 0.6148759 1.920752 0.2143484 1.957133 0.2235522 1.957133 0.2143483 1.061048 0.9326534 1.051844 0.9072378 1.051845 0.9326536 1.148526 0.9326536 1.157729 0.907238 1.148526 0.9072379 1.000488 0.3205851 1.044068 0.2944945 1.000488 0.2944943 1.044068 6.73867e-4 1.000488 0.2051817 1.044068 0.2051816 1.364925 0.252813 1.373903 0.2140727 1.364925 0.2140727 1.730731 0.9391972 1.944592 0.8284353 1.730731 0.8284351 1.000488 0.2528129 1.044068 0.28561 1.044068 0.2528129 1.945016 0.7516131 1.920101 0.7424094 1.920101 0.7516131 1.883598 0.2327569 1.918286 0.36029 1.918287 0.2327569 1.710524 0.4326251 1.626433 0.4419283 1.718715 0.4958242 1.505545 0.3329566 1.469512 0.3205853 1.469512 0.3329566 1.044068 0.2528129 1.053018 0.2140728 1.044068 0.2140728 1.179276 0.2140728 1.188231 0.252813 1.188232 0.2140728 1.318602 0.2856103 1.295579 0.2944474 1.318602 0.2944474 1.318602 0.2528129 1.295579 0.2856099 1.318602 0.2856103 1.364925 0.2944475 1.318602 0.2856103 1.318602 0.2944474 1.364925 0.252813 1.318602 0.2856103 1.364925 0.28561 1.272555 0.2140727 1.188232 0.2052192 1.188232 0.2140728 1.295579 0.2140727 1.318602 0.2528129 1.318602 0.2140727 1.272555 0.2140727 1.188231 0.252813 1.272555 0.2528129 1.318602 0.2052192 1.295579 4.88289e-4 1.295579 0.205219 1.364925 0.2052192 1.318603 4.88513e-4 1.318602 0.2052192 1.505545 0.2528129 1.469512 0.2140727 1.469512 0.2528128 1.505545 0.2140728 1.469512 0.2051753 1.469512 0.2140727 1.469512 5.12323e-4 1.505545 0.2051752 1.505545 5.12315e-4 1.505545 0.2528129 1.469512 0.2856102 1.505545 0.2856101 1.730967 0.3348015 1.881784 0.5486628 1.881784 0.3348016 1.000488 0.2528129 1.044068 0.2140728 1.000488 0.2140725 1.730967 0.5486626 1.878873 0.5573942 1.881784 0.5486628 1.721999 0.831346 1.730731 0.9391972 1.730731 0.8284351 1.14343 0.01716881 1.137722 0.007961034 1.136949 0.01433765 1.152668 0.06678771 1.136054 0.05899429 1.14918 0.07562226 1.136949 0.01433765 1.103101 0.006463944 1.102993 0.01307231 1.152293 0.02071493 1.14343 0.01716881 1.145941 0.02213335 1.12823 0.0844019 1.136054 0.05899429 1.123577 0.06251293 1.446652 0.9357835 1.424507 0.9265977 1.424507 0.9357835 1.101071 0.1931164 1.128612 0.2023019 1.128612 0.1931164 1.07353 0.2023016 1.101071 0.1931164 1.07353 0.1931163 1.449634 0.9357835 1.446652 0.9265977 1.446652 0.9357835 1.554871 0.9247831 1.541136 0.9155978 1.541137 0.9247834 1.12823 0.0844019 1.102014 0.09187269 1.129347 0.09187269 1.102368 0.06344956 1.122161 0.05621325 1.102452 0.05688887 1.139571 0.02124476 1.136949 0.01433765 1.13594 0.01979029 1.067514 8.04474e-4 1.057892 0.01086807 1.068279 0.006764054 1.133425 0.0527479 1.142777 0.05496656 1.138665 0.04879873 1.13594 0.01979029 1.102993 0.01307231 1.102902 0.01896369 1.137722 0.007961034 1.103204 4.88464e-4 1.103101 0.006463944 1.145941 0.02213335 1.139571 0.02124476 1.14054 0.0235123 1.071551 0.05187094 1.081175 0.06195604 1.082787 0.05568909 1.15626 0.1844575 1.128612 0.1931164 1.15626 0.1931163 1.081175 0.06195604 1.102103 0.08445197 1.102368 0.06344956 1.138665 0.04879873 1.14598 0.04982274 1.140609 0.0445531 1.068847 0.01318633 1.103101 0.006463944 1.068279 0.006764054 1.48879 0.9357835 1.454137 0.9265977 1.454137 0.9357835 1.12989 0.1608373 1.139076 0.1680715 1.139076 0.1608373 1.149798 0.1758696 1.15626 0.1666837 1.149798 0.1666839 1.621477 0.9247831 1.631649 0.9155975 1.621477 0.9155975 1.07595 0.08376377 1.102014 0.09187269 1.102103 0.08445197 1.102368 0.06344956 1.082787 0.05568909 1.081175 0.06195604 1.059615 0.0207507 1.066018 0.02002781 1.062268 0.01583838 1.138676 0.00206077 1.147923 0.01234704 1.152043 0.007921338 1.06636 0.04771524 1.058948 0.04857367 1.06206 0.053842 1.069677 0.01867198 1.102993 0.01307231 1.068847 0.01318633 1.074501 0.1844576 1.101071 0.1931164 1.101071 0.1844576 1.364925 0.3329192 1.318602 0.3452491 1.364925 0.3452492 1.918286 0.36029 1.883715 0.3694932 1.918286 0.3694939 1.295579 0.2856099 1.272555 0.2944474 1.295579 0.2944474 1.906096 0.9410116 1.942511 0.9521344 1.942511 0.9410114 1.188232 0.3205384 1.272555 0.2944474 1.188232 0.2944475 1.318602 0.3329197 1.364925 0.3205381 1.318602 0.3205383 1.061048 0.9072378 1.148526 0.9326536 1.148526 0.9072379 1.920101 0.7871531 1.945016 0.7608169 1.920101 0.7608169 1.870277 0.7697482 1.71946 0.8119004 1.870277 0.8119004 1.209085 0.9228498 1.166933 0.9326535 1.209086 0.9326535 1.188231 0.252813 1.179276 0.28561 1.188232 0.28561 1.053018 0.28561 1.044068 0.2528129 1.044068 0.28561 1.272555 0.2856099 1.188232 0.2944475 1.272555 0.2944474 1.945016 0.6056721 1.920101 0.5964685 1.920101 0.6056721 1.364925 0.2052192 1.318602 0.2140727 1.364925 0.2140727 1.318602 0.2140727 1.364925 0.252813 1.364925 0.2140727 1.272555 0.2140727 1.295579 0.205219 1.272555 0.2052192 1.272555 4.88297e-4 1.188232 0.2052192 1.272555 0.2052192 1.272555 0.3329195 1.188232 0.3205384 1.188232 0.3329193 1.469512 0.3205853 1.505545 0.2944943 1.469512 0.2944943 1.867367 0.7610166 1.71946 0.769748 1.870277 0.7697482 1.062268 0.01583838 1.068279 0.006764054 1.057892 0.01086807 1.068732 0.05807965 1.051834 0.06548821 1.05513 0.07444918 1.053269 0.01916384 1.062268 0.01583838 1.057892 0.01086807 1.424507 0.9357835 1.419383 0.9265977 1.419383 0.9357835 1.558196 0.9265977 1.553072 0.9357835 1.558196 0.9357835 1.389918 0.9247831 1.379746 0.9155975 1.379746 0.9247834 1.147923 0.01234704 1.158206 0.01933556 1.152043 0.007921338 1.139076 0.1680715 1.12989 0.1753889 1.139076 0.1753889 1.597833 0.9265977 1.577549 0.9357835 1.597833 0.9357831 1.470259 0.9155978 1.456524 0.9247831 1.470259 0.9247834 1.045883 0.09480309 1.055069 0.08756864 1.045883 0.08756864 1.052344 0.1758695 1.045883 0.1666837 1.045883 0.1758695 1.066018 0.02002781 1.068847 0.01318633 1.062268 0.01583838 1.123577 0.06251293 1.133425 0.0527479 1.122161 0.05621325 1.295579 0.2944474 1.272555 0.3205384 1.295579 0.3205384 1.475616 0.4419285 1.432625 0.4419285 1.432625 0.6419227 1.158206 0.01933556 1.152668 0.06678771 1.15839 0.07515925 1.918286 0.3786976 1.918287 0.592559 1.900266 0.5925588 1.918286 0.3786976 1.900266 0.5925588 1.892347 0.5849624 1.918286 0.3786976 1.892347 0.5849624 1.884066 0.3786978 1.918286 0.3694939 1.884066 0.3786978 1.883715 0.3694932 1.156644 0.3412187 1.045883 0.2990664 1.156644 0.2990664 1.957133 0.3386409 1.957133 0.5525013 1.940316 0.5525014 1.957133 0.3386409 1.940316 0.5525014 1.932278 0.5449053 1.957133 0.3386409 1.932278 0.5449053 1.920751 0.3386411 1.460565 0.2528128 1.373903 0.2140727 1.460565 0.2140728 1.428085 0.1316481 1.463422 0.1205881 1.463422 0.1316481 1.272555 0.2528129 1.188232 0.28561 1.188231 0.252813 1.920101 0.7424094 1.945016 0.6148759 1.945016 0.7424094 1.432625 0.4419285 1.475616 0.4326248 1.475616 0.4419285 1.900266 4.88286e-4 1.918286 4.88286e-4 1.918287 0.2143492 1.892347 0.008084595 1.900266 4.88286e-4 1.918287 0.2143492 1.892347 0.008084595 1.918287 0.2143492 1.884065 0.2143492 1.940316 4.88303e-4 1.957133 4.88287e-4 1.957133 0.2143483 1.932278 0.008084475 1.940316 4.88303e-4 1.957133 0.2143483 1.932278 0.008084475 1.957133 0.2143483 1.920752 0.2143484 1.179276 0.28561 1.053018 0.2528129 1.179276 0.2528129 1.935713 0.8029695 1.924004 0.7990155 1.920101 0.7871531 1.945016 0.8029695 1.935713 0.8029695 1.920101 0.7871531 1.920101 0.570132 1.924004 0.5582697 1.935713 0.5543157 1.920101 0.570132 1.935713 0.5543157 1.945016 0.5543156 1.000488 0.3205851 1.044068 0.3329567 1.000488 0.3329567 1.272555 0.2856099 1.295579 0.252813 1.295579 0.2856099 1.193269 0.907238 1.205131 0.9111408 1.209085 0.9228498 1.166933 0.9072378 1.193269 0.907238 1.209085 0.9228498 1.000488 0.92285 1.004442 0.9111411 1.016304 0.907238 1.000488 0.92285 1.016304 0.907238 1.042641 0.9072379 1.728519 0.4506204 1.728519 0.4958242 1.718715 0.4958242 1.710524 0.4326251 1.728519 0.4506204 1.718715 0.4958242 1.710524 0.4326251 1.725179 0.4359653 1.728519 0.4506204 1.626433 0.4419283 1.718715 0.4958242 1.432625 0.6419227 1.272555 0.2528129 1.295579 0.2140727 1.295579 0.252813 1.718715 0.4958242 1.718715 0.6065858 1.432625 0.6419227 1.432625 0.6419227 1.475616 0.4419285 1.626433 0.4419283 1.718715 0.6065858 1.710385 0.6419227 1.432625 0.6419227 1.731102 0.7581059 1.858635 0.7581059 1.867367 0.7610166 1.867367 0.7610166 1.722371 0.7610161 1.731102 0.7581059 1.870142 0.5603047 1.742609 0.5603047 1.733877 0.5573942 1.733877 0.5573942 1.878873 0.5573942 1.870142 0.5603047 1.719089 0.9275556 1.719089 0.8400775 1.721999 0.831346 1.721999 0.831346 1.721999 0.9362868 1.719089 0.9275556 1.057524 0.2874242 1.145002 0.2874242 1.153734 0.2903351 1.153734 0.2903351 1.048793 0.2903351 1.057524 0.2874242 1.14918 0.07562226 1.141682 0.0840274 1.136054 0.05899429 1.142777 0.05496656 1.14598 0.04982274 1.152668 0.06678771 1.449634 0.9265977 1.454137 0.9357835 1.449634 0.9357835 1.565234 0.9357835 1.577549 0.9265977 1.577549 0.9357835 1.444498 0.9247831 1.456524 0.9155978 1.456524 0.9247831 1.379746 0.9265977 1.40003 0.9357835 1.379746 0.9357835 1.047357 0.01762789 1.051834 0.06548821 1.045888 0.07377058 1.152293 0.02071493 1.14598 0.04982274 1.145941 0.02213335 1.071551 0.05187094 1.06206 0.053842 1.06636 0.04771524 1.14918 0.07562226 1.152668 0.06678771 1.15839 0.07515925 1.15839 0.07515925 1.153132 0.08474558 1.14918 0.07562226 1.068279 0.006764054 1.103204 4.88464e-4 1.103101 0.006463944 1.141682 0.0840274 1.153132 0.08474558 1.129347 0.09187269 1.127641 0.1844576 1.101071 0.1931164 1.101071 0.1844576 1.129347 0.09187269 1.12823 0.0844019 1.141682 0.0840274 1.141682 0.0840274 1.14918 0.07562226 1.153132 0.08474558 1.15626 0.1758696 1.15626 0.1844575 1.127641 0.1844576 1.127641 0.1844576 1.149798 0.1758696 1.15626 0.1758696 1.064468 0.04335635 1.059615 0.0207507 1.064993 0.02227306 1.123577 0.06251293 1.102103 0.08445197 1.102368 0.06344956 1.068732 0.05807965 1.062461 0.08306509 1.05513 0.07444918 1.051834 0.06548821 1.058948 0.04857367 1.06206 0.053842 1.523443 0.9357835 1.527945 0.9265979 1.527945 0.9357835 1.505697 0.9155978 1.541137 0.9247834 1.505697 0.9247834 1.48879 0.9357835 1.523443 0.9265977 1.523443 0.9357835 1.07353 0.1931163 1.045883 0.2023016 1.045883 0.193116 1.389918 0.9247831 1.444498 0.9155978 1.444498 0.9247831 1.554871 0.9155978 1.566898 0.9247831 1.554871 0.9247831 1.053269 0.01916384 1.058948 0.04857367 1.051834 0.06548821 1.140609 0.0445531 1.145941 0.02213335 1.14598 0.04982274 1.05513 0.07444918 1.050949 0.0835188 1.045888 0.07377058 1.045888 0.07377058 1.051834 0.06548821 1.05513 0.07444918 1.062461 0.08306509 1.074652 0.0912249 1.050949 0.0835188 1.045883 0.1844576 1.07353 0.1931163 1.045883 0.193116 1.074652 0.0912249 1.062461 0.08306509 1.07595 0.08376377 1.062461 0.08306509 1.050949 0.0835188 1.05513 0.07444918 1.045883 0.1758695 1.052344 0.1758695 1.074501 0.1844576 1.074501 0.1844576 1.045883 0.1844576 1.045883 0.1758695 1.295579 0.205219 1.318602 0.2140727 1.295579 0.2140727 1.318602 0.3329197 1.295579 0.3452492 1.295579 0.3329195 1.884241 0.9410114 1.862386 0.952134 1.862386 0.9410116 1.920263 0.223552 1.957133 0.2327558 1.920101 0.2327558 1.318602 0.3205383 1.364925 0.2944475 1.364925 0.3205381 1.957133 0.3202335 1.920101 0.2327558 1.957133 0.2327558 1.157729 0.907238 1.166933 0.9326535 1.157729 0.9326534 1.044068 0.3329567 1.000488 0.3452001 1.000488 0.3329567 1.042641 0.9326536 1.000488 0.92285 1.042641 0.9072379 1.728519 0.6419227 1.718715 0.6065858 1.728519 0.6065858 1.053018 0.2528129 1.179276 0.2140728 1.179276 0.2528129 1.042641 0.9072379 1.051845 0.9326536 1.042641 0.9326536 1.000488 0.28561 1.044068 0.2944945 1.000488 0.2944943 1.364925 0.252813 1.373903 0.28561 1.364925 0.28561 1.373903 0.28561 1.460565 0.2528128 1.460565 0.2856102 1.469512 0.2528128 1.460565 0.2856102 1.460565 0.2528128 1.460565 0.2140728 1.469512 0.2528128 1.460565 0.2528128 1.044068 0.2051816 1.000488 0.2140725 1.000488 0.2051817 1.469512 0.2944943 1.505545 0.2856101 1.505545 0.2944943 1.156644 0.2990664 1.048793 0.2903351 1.153734 0.2903351 1.530928 0.9357835 1.553072 0.9265979 1.553072 0.9357835 1.558196 0.9357835 1.565234 0.9265977 1.565234 0.9357835 1.527945 0.9357835 1.530928 0.9265979 1.530928 0.9357835 1.057892 0.01086807 1.047357 0.01762789 1.053874 0.006297409 1.045883 0.09480309 1.055068 0.1021202 1.045883 0.1021202 1.07595 0.08376377 1.068732 0.05807965 1.081175 0.06195604 1.15626 0.2023016 1.128612 0.1931164 1.15626 0.1931163 1.412345 0.9265977 1.419383 0.9357835 1.412345 0.9357835 1.566897 0.9155978 1.621477 0.9247831 1.566898 0.9247831 1.40003 0.9265977 1.412345 0.9357835 1.40003 0.9357835 1.470259 0.9247834 1.505697 0.9155978 1.505697 0.9247834 1.295579 4.88289e-4 1.272555 0.2052192 1.272555 4.88297e-4 1.295579 0.3205384 1.318602 0.2944474 1.318602 0.3205383 1.295579 0.3452492 1.272555 0.3329195 1.295579 0.3329195 1.318602 0.3205383 1.295579 0.3329195 1.295579 0.3205384 1.295579 0.3329195 1.272555 0.3205384 1.295579 0.3205384 1.945016 0.5964685 1.920101 0.570132 1.945016 0.5543156 1.906096 0.9521344 1.884241 0.9410114 1.906096 0.9410116 1.791454 0.9521344 1.862386 0.9410116 1.862386 0.952134 1.469512 0.3452002 1.505545 0.3329566 1.505545 0.3452002 1.884065 0.2143492 1.918286 0.2235528 1.883715 0.2235527 1.883715 0.2235527 1.918287 0.2327569 1.883598 0.2327569 1.957133 0.3294374 1.920751 0.3386411 1.920264 0.3294375 1.957133 0.3202335 1.920264 0.3294375 1.920101 0.3202334 1.272555 0.3452491 1.188232 0.3329193 1.272555 0.3329195 1.920101 0.7516131 1.945016 0.7608169 1.920101 0.7608169 1.123011 0.05257523 1.08002 0.04160183 1.123011 0.04160183 1.945016 0.6148759 1.920101 0.6056721 1.945016 0.6056721 1.920752 0.2143484 1.957133 0.2235522 1.920263 0.223552 1.051844 0.9072378 1.061048 0.9326534 1.051845 0.9326536 1.148526 0.9326536 1.157729 0.907238 1.157729 0.9326534 1.044068 0.2944945 1.000488 0.3205851 1.000488 0.2944943 1.000488 0.2051817 1.044068 6.73867e-4 1.044068 0.2051816 1.364925 0.252813 1.373903 0.2140727 1.373903 0.2528129 1.944592 0.8284353 1.730731 0.9391972 1.730731 0.8284351 1.000488 0.2528129 1.044068 0.28561 1.000488 0.28561 1.945016 0.7516131 1.920101 0.7424094 1.945016 0.7424094 1.918286 0.36029 1.883598 0.2327569 1.918287 0.2327569 1.710524 0.4326251 1.626433 0.4419283 1.626433 0.4326247 1.469512 0.3205853 1.505545 0.3329566 1.469512 0.3329566 1.044068 0.2528129 1.053018 0.2140728 1.053018 0.2528129 1.179276 0.2140728 1.188231 0.252813 1.179276 0.2528129 1.295579 0.2944474 1.318602 0.2856103 1.318602 0.2944474 1.295579 0.2856099 1.318602 0.2528129 1.318602 0.2856103 1.364925 0.2944475 1.318602 0.2856103 1.364925 0.28561 1.318602 0.2856103 1.364925 0.252813 1.364925 0.28561 1.272555 0.2140727 1.188232 0.2052192 1.272555 0.2052192 1.295579 0.2140727 1.318602 0.2528129 1.295579 0.252813 1.188231 0.252813 1.272555 0.2140727 1.272555 0.2528129 1.318602 0.2052192 1.295579 4.88289e-4 1.318603 4.88513e-4 1.364925 0.2052192 1.318603 4.88513e-4 1.364925 4.88281e-4 1.469512 0.2140727 1.505545 0.2528129 1.469512 0.2528128 1.505545 0.2140728 1.469512 0.2051753 1.505545 0.2051752 1.505545 0.2051752 1.469512 5.12323e-4 1.505545 5.12315e-4 1.505545 0.2528129 1.469512 0.2856102 1.469512 0.2528128 1.881784 0.5486628 1.730967 0.3348015 1.881784 0.3348016 1.000488 0.2528129 1.044068 0.2140728 1.044068 0.2528129 1.730967 0.5486626 1.878873 0.5573942 1.733877 0.5573942 1.730731 0.9391972 1.721999 0.831346 1.730731 0.8284351 1.14343 0.01716881 1.137722 0.007961034 1.147923 0.01234704 1.152668 0.06678771 1.136054 0.05899429 1.142777 0.05496656 1.136949 0.01433765 1.103101 0.006463944 1.137722 0.007961034 1.152293 0.02071493 1.14343 0.01716881 1.147923 0.01234704 1.136054 0.05899429 1.12823 0.0844019 1.123577 0.06251293 1.424507 0.9265977 1.446652 0.9357835 1.424507 0.9357835 1.128612 0.2023019 1.101071 0.1931164 1.128612 0.1931164 1.101071 0.1931164 1.07353 0.2023016 1.07353 0.1931163 1.446652 0.9265977 1.449634 0.9357835 1.446652 0.9357835 1.541136 0.9155978 1.554871 0.9247831 1.541137 0.9247834 1.12823 0.0844019 1.102014 0.09187269 1.102103 0.08445197 1.102368 0.06344956 1.122161 0.05621325 1.123577 0.06251293 1.139571 0.02124476 1.136949 0.01433765 1.14343 0.01716881 1.067514 8.04474e-4 1.057892 0.01086807 1.053874 0.006297409 1.133425 0.0527479 1.142777 0.05496656 1.136054 0.05899429 1.13594 0.01979029 1.102993 0.01307231 1.136949 0.01433765 1.103204 4.88464e-4 1.137722 0.007961034 1.103101 0.006463944 1.145941 0.02213335 1.139571 0.02124476 1.14343 0.01716881 1.081175 0.06195604 1.071551 0.05187094 1.082787 0.05568909 1.15626 0.1844575 1.128612 0.1931164 1.127641 0.1844576 1.081175 0.06195604 1.102103 0.08445197 1.07595 0.08376377 1.138665 0.04879873 1.14598 0.04982274 1.142777 0.05496656 1.068847 0.01318633 1.103101 0.006463944 1.102993 0.01307231 1.454137 0.9265977 1.48879 0.9357835 1.454137 0.9357835 1.139076 0.1680715 1.12989 0.1608373 1.139076 0.1608373 1.149798 0.1758696 1.15626 0.1666837 1.15626 0.1758696 1.621477 0.9247831 1.631649 0.9155975 1.631649 0.9247834 1.07595 0.08376377 1.102014 0.09187269 1.074652 0.0912249 1.102368 0.06344956 1.082787 0.05568909 1.102452 0.05688887 1.059615 0.0207507 1.066018 0.02002781 1.064993 0.02227306 1.138676 0.00206077 1.147923 0.01234704 1.137722 0.007961034 1.06636 0.04771524 1.058948 0.04857367 1.064468 0.04335635 1.069677 0.01867198 1.102993 0.01307231 1.102902 0.01896369 1.074501 0.1844576 1.101071 0.1931164 1.07353 0.1931163 1.364925 0.3329192 1.318602 0.3452491 1.318602 0.3329197 1.918286 0.36029 1.883715 0.3694932 1.883598 0.36029 1.272555 0.2944474 1.295579 0.2856099 1.295579 0.2944474 1.906096 0.9410116 1.942511 0.9521344 1.906096 0.9521344 1.272555 0.2944474 1.188232 0.3205384 1.188232 0.2944475 1.318602 0.3329197 1.364925 0.3205381 1.364925 0.3329192 1.061048 0.9072378 1.148526 0.9326536 1.061048 0.9326534 1.920101 0.7871531 1.945016 0.7608169 1.945016 0.8029695 1.71946 0.8119004 1.870277 0.7697482 1.870277 0.8119004 1.209085 0.9228498 1.166933 0.9326535 1.166933 0.9072378 1.188231 0.252813 1.179276 0.28561 1.179276 0.2528129 1.053018 0.28561 1.044068 0.2528129 1.053018 0.2528129 1.188232 0.2944475 1.272555 0.2856099 1.272555 0.2944474 1.945016 0.6056721 1.920101 0.5964685 1.945016 0.5964685 1.364925 0.2052192 1.318602 0.2140727 1.318602 0.2052192 1.318602 0.2140727 1.364925 0.252813 1.318602 0.2528129 1.272555 0.2140727 1.295579 0.205219 1.295579 0.2140727 1.272555 4.88297e-4 1.188232 0.2052192 1.188232 4.88337e-4 1.272555 0.3329195 1.188232 0.3205384 1.272555 0.3205384 1.505545 0.2944943 1.469512 0.3205853 1.469512 0.2944943 1.71946 0.769748 1.867367 0.7610166 1.870277 0.7697482 1.062268 0.01583838 1.068279 0.006764054 1.068847 0.01318633 1.051834 0.06548821 1.068732 0.05807965 1.05513 0.07444918 1.053269 0.01916384 1.062268 0.01583838 1.059615 0.0207507 1.419383 0.9265977 1.424507 0.9357835 1.419383 0.9357835 1.553072 0.9357835 1.558196 0.9265977 1.558196 0.9357835 1.389918 0.9247831 1.379746 0.9155975 1.389918 0.9155975 1.147923 0.01234704 1.158206 0.01933556 1.152293 0.02071493 1.139076 0.1680715 1.12989 0.1753889 1.125262 0.1680715 1.577549 0.9357835 1.597833 0.9265977 1.597833 0.9357831 1.456524 0.9247831 1.470259 0.9155978 1.470259 0.9247834 1.055069 0.08756864 1.045883 0.09480309 1.045883 0.08756864 1.052344 0.1758695 1.045883 0.1666837 1.052344 0.1666837 1.066018 0.02002781 1.068847 0.01318633 1.069677 0.01867198 1.133425 0.0527479 1.123577 0.06251293 1.122161 0.05621325 1.272555 0.3205384 1.295579 0.2944474 1.295579 0.3205384 1.475616 0.4419285 1.432625 0.6419227 1.432625 0.4419285 1.158206 0.01933556 1.152668 0.06678771 1.152293 0.02071493 0.1602049 4.88286e-4 0.1656056 0.1149616 0.1656055 4.88286e-4 0.3668324 4.88286e-4 0.4252825 0.1296843 0.4379963 4.88286e-4 0.1602049 0.1149616 0.1656055 0.1191003 0.1656056 0.1149616 0.718721 0.1367283 0.8513208 0.18937 0.8513209 0.1367283 0.5584729 0.8715661 0.6886763 0.8886547 0.6886763 0.8715661 0.122774 0.03978753 0.06735414 0.02267414 0.07119172 0.03978765 0.7187211 4.88286e-4 0.8513209 0.1268674 0.8513208 4.88286e-4 0.9742742 0.475126 0.9995117 0.3395631 0.9742742 0.3395631 0.9742742 0.7152901 0.9995117 0.4839324 0.9742742 0.4839326 0.4301471 0.09963738 0.4476855 0.1131566 0.4476855 0.09963732 0.7033466 0.1367283 0.718721 0.1324492 0.7033466 0.1322978 0.9742742 0.4795293 0.9995117 0.4839324 0.9995117 0.4795292 0.1201953 0.6398431 0.1241632 0.6338987 0.1201952 0.6338989 0.9672788 0.8244635 0.9849687 0.8827466 0.9859736 0.8247719 0.9878022 0.1162673 0.9589475 0.1224743 0.9878022 0.1224736 0.4394726 0.4166052 0.46257 0.2874245 0.4269233 0.2874243 0.9589475 0.1286842 0.9878022 0.3377475 0.9878022 0.1286842 0.1656056 0.123239 0.160205 0.1693082 0.1656055 0.1693081 0.9589474 0.1162674 0.9878022 0.08591735 0.969421 0.08381986 0.9507004 0.7686162 0.9672788 0.7764334 0.9672788 0.7686162 0.9589475 0.1224743 0.9878022 0.1286842 0.9878022 0.1224736 0.1656055 0.1191003 0.1602049 0.123239 0.1656056 0.123239 0.2135179 0.7880615 4.88282e-4 0.7880615 0.2079482 0.9054236 0.7033466 4.88286e-4 0.718721 0.1268674 0.7187211 4.88286e-4 0.851321 0.2727802 0.718721 0.3340762 0.8513208 0.3212934 0.04630947 0.2041161 0.09486085 0.2091332 0.09455049 0.2041161 0.5634874 0.9075481 0.6936855 0.8904688 0.5634874 0.8904688 0.1370818 0.1372556 0.1542612 0.08812946 0.1370818 0.09151941 0.5634765 0.8697519 0.6936799 0.8526635 0.5634765 0.8526635 0.9507005 0.554348 0.9672788 0.7686162 0.9672788 0.5542747 0.1102058 0.9344678 0.07455897 0.9395559 0.1102058 0.9395559 0.158074 0.19422 0.1752538 0.1711225 0.158074 0.1711224 0.9698835 0.03194242 0.9878022 0.001010596 0.9589475 5.04342e-4 0.4497116 0.08430391 0.4321468 0.09782314 0.4497116 0.09782314 0.718721 0.1324492 0.7033464 0.1268675 0.7033466 0.1322978 0.3667389 0.1830862 0.4183209 0.1695669 0.3667389 0.1695669 0.1241632 0.6338987 0.1281312 0.6398431 0.1281311 0.6338989 0.9672788 0.7764334 0.9507007 0.7841923 0.9672788 0.7841923 0.8513209 0.1312991 0.718721 0.1268674 0.718721 0.1324492 5.41001e-4 0.9344677 0.0719918 0.939536 0.0722782 0.934468 0.9672788 0.8824383 0.9672788 0.8244635 0.9507004 0.9089362 0.558473 0.8697519 0.5634765 0.8526635 0.558473 0.8526635 0.6886763 0.8715661 0.6936799 0.8886547 0.6936799 0.8715661 0.3343058 0.6398431 0.1281311 0.6338989 0.1281312 0.6398431 0.718721 0.1367283 0.8513209 0.1312991 0.718721 0.1324492 0.7033466 0.3603313 0.7187211 0.2598316 0.718721 0.2077418 0.7033466 0.3603313 0.718721 0.3340762 0.7187211 0.2598316 0.7033466 0.3603313 0.718721 0.3603313 0.718721 0.3340762 0.9742742 0.475126 0.9995117 0.4795292 0.9995117 0.4751258 0.9698835 0.03194242 0.9589474 0.1162674 0.969421 0.08381986 0.7033466 0.1367283 0.718721 0.2077418 0.718721 0.1367283 0.5584729 0.9075482 0.5634874 0.8904688 0.5584731 0.8904688 4.88281e-4 0.6398431 0.1201952 0.6338989 4.88281e-4 0.6338987 1.160205 4.88286e-4 1.165606 0.1149616 1.160205 0.1149616 1.366832 4.88286e-4 1.425282 0.1296843 1.379546 0.1296846 1.165606 0.1191003 1.160205 0.1149616 1.165606 0.1149616 1.851321 0.18937 1.718721 0.1367283 1.851321 0.1367283 1.558473 0.8715661 1.688676 0.8886547 1.558473 0.8886547 1.122774 0.03978753 1.067354 0.02267414 1.12673 0.0226742 1.718721 4.88286e-4 1.851321 0.1268674 1.718721 0.1268674 1.999512 0.3395631 1.974274 0.475126 1.974274 0.3395631 1.999512 0.4839324 1.974274 0.7152901 1.974274 0.4839326 1.430147 0.09963738 1.447685 0.1131566 1.430147 0.117868 1.703347 0.1367283 1.718721 0.1324492 1.718721 0.1367283 1.999512 0.4839324 1.974274 0.4795293 1.999512 0.4795292 1.124163 0.6338987 1.120195 0.6398431 1.120195 0.6338989 1.984969 0.8827466 1.967279 0.8244635 1.985974 0.8247719 1.987802 0.1162673 1.958947 0.1224743 1.958947 0.1162674 1.439473 0.4166052 1.46257 0.2874245 1.46257 0.4166054 1.958947 0.1286842 1.987802 0.3377475 1.958947 0.3377504 1.165606 0.123239 1.160205 0.1693082 1.160205 0.123239 1.958947 0.1162674 1.987802 0.08591735 1.987802 0.1162673 1.967279 0.7764334 1.9507 0.7686162 1.967279 0.7686162 1.987802 0.1286842 1.958947 0.1224743 1.987802 0.1224736 1.165606 0.1191003 1.160205 0.123239 1.160205 0.1191003 1.213518 0.7880615 1.213518 0.8998538 1.207948 0.9054236 1.718721 0.1268674 1.703346 4.88286e-4 1.718721 4.88286e-4 1.851321 0.2727802 1.718721 0.3340762 1.718721 0.2598316 1.046309 0.2041161 1.094861 0.2091332 1.04595 0.2091332 1.693686 0.8904688 1.563487 0.9075481 1.563487 0.8904688 1.137082 0.1372556 1.154261 0.08812946 1.154261 0.1406455 1.69368 0.8526635 1.563477 0.8697519 1.563477 0.8526635 1.9507 0.554348 1.967279 0.7686162 1.9507 0.7686162 1.110206 0.9344678 1.074559 0.9395559 1.07421 0.9344678 1.158074 0.19422 1.175254 0.1711225 1.175254 0.1976141 1.969883 0.03194242 1.987802 0.001010596 1.987802 0.0278356 1.432147 0.09782314 1.449712 0.08430391 1.449712 0.09782314 1.703346 0.1268675 1.718721 0.1324492 1.703346 0.1322978 1.418321 0.1695669 1.366739 0.1830862 1.366739 0.1695669 1.124163 0.6338987 1.128131 0.6398431 1.124163 0.6398431 1.967279 0.7764334 1.950701 0.7841923 1.950701 0.7764334 1.718721 0.1268674 1.851321 0.1312991 1.718721 0.1324492 1.000541 0.9344677 1.071992 0.939536 1.000827 0.939536 1.967279 0.8244635 1.967279 0.8824383 1.9507 0.9089362 1.563477 0.8526635 1.558473 0.8697519 1.558473 0.8526635 1.688676 0.8715661 1.69368 0.8886547 1.688676 0.8886547 1.334306 0.6398431 1.128131 0.6338989 1.334306 0.6338987 1.718721 0.1367283 1.851321 0.1312991 1.851321 0.1367283 1.703346 0.3603313 1.718721 0.2077418 1.718721 0.2598316 1.703346 0.3603313 1.718721 0.2598316 1.718721 0.3340762 1.703346 0.3603313 1.718721 0.3340762 1.718721 0.3603313 1.999512 0.4795292 1.974274 0.475126 1.999512 0.4751258 1.969883 0.03194242 1.958947 0.1162674 1.958947 5.04342e-4 1.718721 0.2077418 1.703347 0.1367283 1.718721 0.1367283 1.563487 0.8904688 1.558473 0.9075482 1.558473 0.8904688 1.000488 0.6398431 1.120195 0.6338989 1.120195 0.6398431 1.160205 4.88286e-4 1.165606 0.1149616 1.160205 0.1149616 1.366832 4.88286e-4 1.425282 0.1296843 1.379546 0.1296846 1.165606 0.1191003 1.160205 0.1149616 1.165606 0.1149616 1.851321 0.18937 1.718721 0.1367283 1.851321 0.1367283 1.558473 0.8715661 1.688676 0.8886547 1.558473 0.8886547 1.122774 0.03978753 1.067354 0.02267414 1.12673 0.0226742 1.718721 4.88286e-4 1.851321 0.1268674 1.718721 0.1268674 1.999512 0.3395631 1.974274 0.475126 1.974274 0.3395631 1.999512 0.4839324 1.974274 0.7152901 1.974274 0.4839326 1.430147 0.09963738 1.447685 0.1131566 1.430147 0.117868 1.703347 0.1367283 1.718721 0.1324492 1.718721 0.1367283 1.999512 0.4839324 1.974274 0.4795293 1.999512 0.4795292 1.124163 0.6338987 1.120195 0.6398431 1.120195 0.6338989 1.984969 0.8827466 1.967279 0.8244635 1.985974 0.8247719 1.987802 0.1162673 1.958947 0.1224743 1.958947 0.1162674 1.439473 0.4166052 1.46257 0.2874245 1.46257 0.4166054 1.958947 0.1286842 1.987802 0.3377475 1.958947 0.3377504 1.165606 0.123239 1.160205 0.1693082 1.160205 0.123239 1.958947 0.1162674 1.987802 0.08591735 1.987802 0.1162673 1.967279 0.7764334 1.9507 0.7686162 1.967279 0.7686162 1.987802 0.1286842 1.958947 0.1224743 1.987802 0.1224736 1.165606 0.1191003 1.160205 0.123239 1.160205 0.1191003 1.213518 0.7880615 1.213518 0.8998538 1.207948 0.9054236 1.718721 0.1268674 1.703346 4.88286e-4 1.718721 4.88286e-4 1.851321 0.2727802 1.718721 0.3340762 1.718721 0.2598316 1.046309 0.2041161 1.094861 0.2091332 1.04595 0.2091332 1.693686 0.8904688 1.563487 0.9075481 1.563487 0.8904688 1.137082 0.1372556 1.154261 0.08812946 1.154261 0.1406455 1.69368 0.8526635 1.563477 0.8697519 1.563477 0.8526635 1.9507 0.554348 1.967279 0.7686162 1.9507 0.7686162 1.110206 0.9344678 1.074559 0.9395559 1.07421 0.9344678 1.158074 0.19422 1.175254 0.1711225 1.175254 0.1976141 1.969883 0.03194242 1.987802 0.001010596 1.987802 0.0278356 1.432147 0.09782314 1.449712 0.08430391 1.449712 0.09782314 1.703346 0.1268675 1.718721 0.1324492 1.703346 0.1322978 1.418321 0.1695669 1.366739 0.1830862 1.366739 0.1695669 1.124163 0.6338987 1.128131 0.6398431 1.124163 0.6398431 1.967279 0.7764334 1.950701 0.7841923 1.950701 0.7764334 1.718721 0.1268674 1.851321 0.1312991 1.718721 0.1324492 1.000541 0.9344677 1.071992 0.939536 1.000827 0.939536 1.967279 0.8244635 1.967279 0.8824383 1.9507 0.9089362 1.563477 0.8526635 1.558473 0.8697519 1.558473 0.8526635 1.688676 0.8715661 1.69368 0.8886547 1.688676 0.8886547 1.334306 0.6398431 1.128131 0.6338989 1.334306 0.6338987 1.718721 0.1367283 1.851321 0.1312991 1.851321 0.1367283 1.703346 0.3603313 1.718721 0.2077418 1.718721 0.2598316 1.703346 0.3603313 1.718721 0.2598316 1.718721 0.3340762 1.703346 0.3603313 1.718721 0.3340762 1.718721 0.3603313 1.999512 0.4795292 1.974274 0.475126 1.999512 0.4751258 1.969883 0.03194242 1.958947 0.1162674 1.958947 5.04342e-4 1.718721 0.2077418 1.703347 0.1367283 1.718721 0.1367283 1.563487 0.8904688 1.558473 0.9075482 1.558473 0.8904688 1.000488 0.6398431 1.120195 0.6338989 1.120195 0.6398431 1.160205 4.88286e-4 1.165606 0.1149616 1.165606 4.88286e-4 1.366832 4.88286e-4 1.425282 0.1296843 1.437996 4.88286e-4 1.160205 0.1149616 1.165606 0.1191003 1.165606 0.1149616 1.718721 0.1367283 1.851321 0.18937 1.851321 0.1367283 1.558473 0.8715661 1.688676 0.8886547 1.688676 0.8715661 1.122774 0.03978753 1.067354 0.02267414 1.071192 0.03978765 1.718721 4.88286e-4 1.851321 0.1268674 1.851321 4.88286e-4 1.974274 0.475126 1.999512 0.3395631 1.974274 0.3395631 1.974274 0.7152901 1.999512 0.4839324 1.974274 0.4839326 1.430147 0.09963738 1.447685 0.1131566 1.447686 0.09963732 1.703347 0.1367283 1.718721 0.1324492 1.703346 0.1322978 1.974274 0.4795293 1.999512 0.4839324 1.999512 0.4795292 1.120195 0.6398431 1.124163 0.6338987 1.120195 0.6338989 1.967279 0.8244635 1.984969 0.8827466 1.985974 0.8247719 1.987802 0.1162673 1.958947 0.1224743 1.987802 0.1224736 1.439473 0.4166052 1.46257 0.2874245 1.426923 0.2874243 1.958947 0.1286842 1.987802 0.3377475 1.987802 0.1286842 1.165606 0.123239 1.160205 0.1693082 1.165606 0.1693081 1.958947 0.1162674 1.987802 0.08591735 1.969421 0.08381986 1.9507 0.7686162 1.967279 0.7764334 1.967279 0.7686162 1.958947 0.1224743 1.987802 0.1286842 1.987802 0.1224736 1.165606 0.1191003 1.160205 0.123239 1.165606 0.123239 1.213518 0.7880615 1.000488 0.7880615 1.207948 0.9054236 1.703346 4.88286e-4 1.718721 0.1268674 1.718721 4.88286e-4 1.851321 0.2727802 1.718721 0.3340762 1.851321 0.3212934 1.046309 0.2041161 1.094861 0.2091332 1.09455 0.2041161 1.563487 0.9075481 1.693686 0.8904688 1.563487 0.8904688 1.137082 0.1372556 1.154261 0.08812946 1.137082 0.09151941 1.563477 0.8697519 1.69368 0.8526635 1.563477 0.8526635 1.9507 0.554348 1.967279 0.7686162 1.967279 0.5542747 1.110206 0.9344678 1.074559 0.9395559 1.110206 0.9395559 1.158074 0.19422 1.175254 0.1711225 1.158074 0.1711224 1.969883 0.03194242 1.987802 0.001010596 1.958947 5.04342e-4 1.449712 0.08430391 1.432147 0.09782314 1.449712 0.09782314 1.718721 0.1324492 1.703346 0.1268675 1.703346 0.1322978 1.366739 0.1830862 1.418321 0.1695669 1.366739 0.1695669 1.124163 0.6338987 1.128131 0.6398431 1.128131 0.6338989 1.967279 0.7764334 1.950701 0.7841923 1.967279 0.7841923 1.851321 0.1312991 1.718721 0.1268674 1.718721 0.1324492 1.000541 0.9344677 1.071992 0.939536 1.072278 0.934468 1.967279 0.8824383 1.967279 0.8244635 1.9507 0.9089362 1.558473 0.8697519 1.563477 0.8526635 1.558473 0.8526635 1.688676 0.8715661 1.69368 0.8886547 1.69368 0.8715661 1.334306 0.6398431 1.128131 0.6338989 1.128131 0.6398431 1.718721 0.1367283 1.851321 0.1312991 1.718721 0.1324492 1.703346 0.3603313 1.718721 0.2598316 1.718721 0.2077418 1.703346 0.3603313 1.718721 0.3340762 1.718721 0.2598316 1.703346 0.3603313 1.718721 0.3603313 1.718721 0.3340762 1.974274 0.475126 1.999512 0.4795292 1.999512 0.4751258 1.969883 0.03194242 1.958947 0.1162674 1.969421 0.08381986 1.703347 0.1367283 1.718721 0.2077418 1.718721 0.1367283 1.558473 0.9075482 1.563487 0.8904688 1.558473 0.8904688 1.000488 0.6398431 1.120195 0.6338989 1.000488 0.6338987 0.9182864 0.3694939 0.9182865 0.3786976 0.8840656 0.3786978 0.1566444 0.3412187 0.04588252 0.3412187 0.04588252 0.2990664 0.4605653 0.2528128 0.3739025 0.2528129 0.3739025 0.2140727 0.4280855 0.1316481 0.4280855 0.1205881 0.4634221 0.1205881 0.2725553 0.2528129 0.2725553 0.2856099 0.1882316 0.28561 0.9201011 0.7424094 0.9201011 0.6148759 0.9450164 0.6148759 0.4326246 0.4419285 0.4326246 0.4326248 0.4756163 0.4326248 0.1792764 0.28561 0.05301833 0.28561 0.05301839 0.2528129 4.88303e-4 0.3205851 0.04406827 0.3205851 0.04406833 0.3329567 0.2725553 0.2856099 0.2725553 0.2528129 0.2955789 0.252813 0.2725553 0.2528129 0.2725553 0.2140727 0.295579 0.2140727 0.4496341 0.9265977 0.4541368 0.9265977 0.4541367 0.9357835 0.5652344 0.9357835 0.5652345 0.9265977 0.5775492 0.9265977 0.4444977 0.9247831 0.4444976 0.9155978 0.456524 0.9155978 0.3797456 0.9265977 0.4000297 0.9265977 0.4000297 0.9357835 0.04735714 0.01762789 0.05326932 0.01916384 0.05183398 0.06548821 0.1522934 0.02071493 0.1526682 0.06678771 0.1459805 0.04982274 0.07155132 0.05187094 0.06873148 0.05807965 0.0620597 0.053842 0.06827884 0.006764054 0.06751406 8.04474e-4 0.1032041 4.88464e-4 0.1276409 0.1844576 0.1286125 0.1931164 0.1010712 0.1931164 0.06446784 0.04335635 0.05894839 0.04857367 0.05961465 0.0207507 0.123577 0.06251293 0.1282298 0.0844019 0.1021029 0.08445197 0.5234426 0.9357835 0.5234427 0.9265977 0.5279453 0.9265979 0.5056975 0.9155978 0.5411366 0.9155978 0.5411367 0.9247834 0.4887897 0.9357835 0.4887897 0.9265977 0.5234427 0.9265977 0.07352977 0.1931163 0.07352977 0.2023016 0.04588282 0.2023016 0.3899179 0.9247831 0.3899179 0.9155975 0.4444976 0.9155978 0.5548712 0.9155978 0.5668975 0.9155978 0.5668978 0.9247831 0.05326932 0.01916384 0.05961465 0.0207507 0.05894839 0.04857367 0.1406086 0.0445531 0.1405403 0.0235123 0.1459411 0.02213335 0.04588252 0.1844576 0.07450091 0.1844576 0.07352977 0.1931163 0.295579 0.205219 0.3186024 0.2052192 0.3186024 0.2140727 0.3186025 0.3329197 0.3186025 0.3452491 0.2955789 0.3452492 0.8842406 0.9410114 0.8842406 0.9521344 0.8623856 0.952134 0.9202634 0.223552 0.9571331 0.2235522 0.9571331 0.2327558 0.3186025 0.3205383 0.3186024 0.2944474 0.3649247 0.2944475 0.9571332 0.3202335 0.9201007 0.3202334 0.9201009 0.2327558 0.1577292 0.907238 0.166933 0.9072378 0.1669332 0.9326535 0.04406833 0.3329567 0.04406833 0.3452001 4.8831e-4 0.3452001 0.04264074 0.9326536 4.8834e-4 0.9326536 4.88282e-4 0.92285 0.728519 0.6419227 0.7103851 0.6419227 0.7187154 0.6065858 0.05301839 0.2528129 0.05301839 0.2140728 0.1792763 0.2140728 0.04264056 0.9072379 0.05184429 0.9072378 0.05184453 0.9326536 4.88281e-4 0.28561 0.04406827 0.28561 0.04406827 0.2944945 0.3649246 0.252813 0.3739025 0.2528129 0.3739026 0.28561 0.3739026 0.28561 0.3739025 0.2528129 0.4605653 0.2528128 0.4695122 0.2528128 0.4695124 0.2856102 0.4605652 0.2856102 0.4605651 0.2140728 0.4695124 0.2140727 0.4695122 0.2528128 0.04406833 0.2051816 0.04406833 0.2140728 4.88345e-4 0.2140725 0.4695124 0.2944943 0.4695124 0.2856102 0.5055451 0.2856101 0.04588252 0.2990664 0.04879301 0.2903351 0.153734 0.2903351 0.5309278 0.9357835 0.5309278 0.9265979 0.5530718 0.9265979 0.558196 0.9357835 0.558196 0.9265977 0.5652345 0.9265977 0.5279453 0.9357835 0.5279453 0.9265979 0.5309278 0.9265979 0.05789202 0.01086807 0.05326932 0.01916384 0.04735714 0.01762789 0.0458827 0.09480309 0.05969667 0.09480309 0.05506843 0.1021202 0.07595032 0.08376377 0.06246048 0.08306509 0.06873148 0.05807965 0.1562597 0.2023016 0.1286125 0.2023019 0.1286125 0.1931164 0.4123449 0.9265977 0.4193832 0.9265977 0.4193831 0.9357835 0.5668975 0.9155978 0.621477 0.9155975 0.6214771 0.9247831 0.4000297 0.9265977 0.4123449 0.9265977 0.4123449 0.9357835 0.4702587 0.9247834 0.4702587 0.9155978 0.5056975 0.9155978 0.2955788 4.88289e-4 0.295579 0.205219 0.2725553 0.2052192 0.2955789 0.3205384 0.295579 0.2944474 0.3186024 0.2944474 0.2955789 0.3452492 0.2725553 0.3452491 0.2725553 0.3329195 0.3186025 0.3205383 0.3186025 0.3329197 0.295579 0.3329195 0.295579 0.3329195 0.2725553 0.3329195 0.2725553 0.3205384 0.9450165 0.5964685 0.9201009 0.5964685 0.9201009 0.570132 0.9060957 0.9521344 0.8842406 0.9521344 0.8842406 0.9410114 0.7914544 0.9521344 0.7914544 0.9410114 0.8623856 0.9410116 0.4695124 0.3452002 0.4695124 0.3329566 0.5055454 0.3329566 0.8840655 0.2143492 0.9182865 0.2143492 0.9182864 0.2235528 0.883715 0.2235527 0.9182864 0.2235528 0.9182868 0.2327569 0.9571332 0.3294374 0.9571333 0.3386409 0.9207512 0.3386411 0.9571332 0.3202335 0.9571332 0.3294374 0.9202635 0.3294375 0.2725553 0.3452491 0.1882315 0.3452492 0.1882315 0.3329193 0.9201009 0.7516131 0.9450165 0.7516131 0.9450165 0.7608169 0.1230109 0.05257523 0.08001965 0.05257523 0.08001965 0.04160183 0.9450164 0.6148759 0.9201011 0.6148759 0.9201011 0.6056721 0.9207516 0.2143484 0.9571332 0.2143483 0.9571331 0.2235522 0.05184429 0.9072378 0.06104779 0.9072378 0.06104815 0.9326534 0.1485259 0.9326536 0.1485257 0.9072379 0.1577292 0.907238 0.04406827 0.2944945 0.04406827 0.3205851 4.88303e-4 0.3205851 4.88343e-4 0.2051817 4.88347e-4 6.73875e-4 0.04406833 6.73867e-4 0.3649246 0.252813 0.3649247 0.2140727 0.3739025 0.2140727 0.944592 0.8284353 0.9445921 0.9391971 0.730731 0.9391972 4.88342e-4 0.2528129 0.04406833 0.2528129 0.04406827 0.28561 0.9450165 0.7516131 0.9201009 0.7516131 0.9201011 0.7424094 0.9182865 0.36029 0.883598 0.36029 0.8835983 0.2327569 0.7105237 0.4326251 0.7187155 0.4958242 0.6264333 0.4419283 0.4695122 0.3205853 0.5055454 0.3205853 0.5055454 0.3329566 0.04406833 0.2528129 0.04406833 0.2140728 0.05301839 0.2140728 0.1792763 0.2140728 0.1882315 0.2140728 0.1882315 0.252813 0.295579 0.2944474 0.295579 0.2856099 0.3186024 0.2856103 0.295579 0.2856099 0.2955789 0.252813 0.3186024 0.2528129 0.3649247 0.2944475 0.3186024 0.2944474 0.3186024 0.2856103 0.3186024 0.2856103 0.3186024 0.2528129 0.3649246 0.252813 0.2725553 0.2140727 0.1882315 0.2140728 0.1882316 0.2052192 0.295579 0.2140727 0.3186024 0.2140727 0.3186024 0.2528129 0.1882315 0.252813 0.1882315 0.2140728 0.2725553 0.2140727 0.3186024 0.2052192 0.295579 0.205219 0.2955788 4.88289e-4 0.3649247 0.2052192 0.3186024 0.2052192 0.3186025 4.88513e-4 0.4695124 0.2140727 0.5055453 0.2140728 0.5055453 0.2528129 0.5055453 0.2140728 0.4695124 0.2140727 0.4695124 0.2051753 0.5055453 0.2051752 0.4695124 0.2051753 0.4695123 5.12323e-4 0.5055453 0.2528129 0.5055451 0.2856101 0.4695124 0.2856102 0.8817839 0.5486628 0.7309666 0.5486626 0.7309666 0.3348015 4.88342e-4 0.2528129 4.88345e-4 0.2140725 0.04406833 0.2140728 0.7309666 0.5486626 0.8817839 0.5486628 0.8788734 0.5573942 0.730731 0.9391972 0.7219995 0.9362868 0.7219994 0.831346 0.1434301 0.01716881 0.1369493 0.01433765 0.1377221 0.007961034 0.1526682 0.06678771 0.1491801 0.07562226 0.1360535 0.05899429 0.1369493 0.01433765 0.1029926 0.01307231 0.1031009 0.006463944 0.1522934 0.02071493 0.1459411 0.02213335 0.1434301 0.01716881 0.1360535 0.05899429 0.1416816 0.0840274 0.1282298 0.0844019 0.4245075 0.9265977 0.4466516 0.9265977 0.4466516 0.9357835 0.1286125 0.2023019 0.1010711 0.2023019 0.1010712 0.1931164 0.1010712 0.1931164 0.1010711 0.2023019 0.07352977 0.2023016 0.4466516 0.9265977 0.4496341 0.9265977 0.449634 0.9357835 0.5411366 0.9155978 0.5548712 0.9155978 0.5548712 0.9247831 0.1282298 0.0844019 0.1293473 0.09187269 0.1020137 0.09187269 0.1023678 0.06344956 0.1024522 0.05688887 0.1221608 0.05621325 0.139571 0.02124476 0.1359398 0.01979029 0.1369493 0.01433765 0.06751406 8.04474e-4 0.06827884 0.006764054 0.05789202 0.01086807 0.1334255 0.0527479 0.1386654 0.04879873 0.1427766 0.05496656 0.1359398 0.01979029 0.1029018 0.01896369 0.1029926 0.01307231 0.1032041 4.88464e-4 0.1386755 0.00206077 0.1377221 0.007961034 0.1459411 0.02213335 0.1405403 0.0235123 0.139571 0.02124476 0.08117532 0.06195604 0.06873148 0.05807965 0.07155132 0.05187094 0.1562597 0.1844575 0.1562598 0.1931163 0.1286125 0.1931164 0.08117532 0.06195604 0.1023678 0.06344956 0.1021029 0.08445197 0.1386654 0.04879873 0.1406086 0.0445531 0.1459805 0.04982274 0.06884676 0.01318633 0.06827884 0.006764054 0.1031009 0.006463944 0.4541368 0.9265977 0.4887897 0.9265977 0.4887897 0.9357835 0.1390759 0.1680715 0.1252617 0.1680715 0.1298903 0.1608373 0.149798 0.1758696 0.149798 0.1666839 0.1562597 0.1666837 0.6214771 0.9247831 0.621477 0.9155975 0.6316491 0.9155975 0.07595032 0.08376377 0.1021029 0.08445197 0.1020137 0.09187269 0.1023678 0.06344956 0.08117532 0.06195604 0.08278739 0.05568909 0.05961465 0.0207507 0.0622676 0.01583838 0.0660178 0.02002781 0.1386755 0.00206077 0.1520432 0.007921338 0.1479231 0.01234704 0.06636029 0.04771524 0.0620597 0.053842 0.05894839 0.04857367 0.06967717 0.01867198 0.06884676 0.01318633 0.1029926 0.01307231 0.07450091 0.1844576 0.1010711 0.1844576 0.1010712 0.1931164 0.3649246 0.3329192 0.3649246 0.3452492 0.3186025 0.3452491 0.9182865 0.36029 0.9182864 0.3694939 0.883715 0.3694932 0.2725553 0.2944474 0.2725553 0.2856099 0.295579 0.2856099 0.9060957 0.9410116 0.9425108 0.9410114 0.9425108 0.9521344 0.2725553 0.2944474 0.2725553 0.3205384 0.1882315 0.3205384 0.3186025 0.3329197 0.3186025 0.3205383 0.3649247 0.3205381 0.06104779 0.9072378 0.1485257 0.9072379 0.1485259 0.9326536 0.9201009 0.7871531 0.9201009 0.7608169 0.9450165 0.7608169 0.7194603 0.8119004 0.7194604 0.769748 0.8702774 0.7697482 0.2090855 0.9228498 0.2090857 0.9326535 0.1669332 0.9326535 0.1882315 0.252813 0.1882316 0.28561 0.1792764 0.28561 0.05301833 0.28561 0.04406827 0.28561 0.04406833 0.2528129 0.1882315 0.2944475 0.1882316 0.28561 0.2725553 0.2856099 0.9450164 0.6056721 0.9201011 0.6056721 0.9201009 0.5964685 0.3649247 0.2052192 0.3649247 0.2140727 0.3186024 0.2140727 0.3186024 0.2140727 0.3649247 0.2140727 0.3649246 0.252813 0.2725553 0.2140727 0.2725553 0.2052192 0.295579 0.205219 0.2725554 4.88297e-4 0.2725553 0.2052192 0.1882316 0.2052192 0.2725553 0.3329195 0.1882315 0.3329193 0.1882315 0.3205384 0.5055453 0.2944943 0.5055454 0.3205853 0.4695122 0.3205853 0.7194604 0.769748 0.7223711 0.7610161 0.867367 0.7610166 0.0622676 0.01583838 0.05789202 0.01086807 0.06827884 0.006764054 0.05183398 0.06548821 0.0620597 0.053842 0.06873148 0.05807965 0.05326932 0.01916384 0.05789202 0.01086807 0.0622676 0.01583838 0.4193832 0.9265977 0.4245075 0.9265977 0.4245074 0.9357835 0.5530717 0.9357835 0.5530718 0.9265979 0.558196 0.9265977 0.3899179 0.9247831 0.3797456 0.9247834 0.3797456 0.9155975 0.1479231 0.01234704 0.1520432 0.007921338 0.1582064 0.01933556 0.1390759 0.1680715 0.1390759 0.1753889 0.1298903 0.1753889 0.5775492 0.9357835 0.5775492 0.9265977 0.5978327 0.9265977 0.456524 0.9247831 0.456524 0.9155978 0.4702587 0.9155978 0.05506855 0.08756864 0.05969667 0.09480309 0.0458827 0.09480309 0.0523439 0.1758695 0.04588252 0.1758695 0.04588282 0.1666837 0.0660178 0.02002781 0.0622676 0.01583838 0.06884676 0.01318633 0.1334255 0.0527479 0.1360535 0.05899429 0.123577 0.06251293 0.2725553 0.3205384 0.2725553 0.2944474 0.295579 0.2944474 0.1582064 0.01933556 0.1583899 0.07515925 0.1526682 0.06678771 1.918286 0.3694939 1.883715 0.3694932 1.884066 0.3786978 1.045883 0.2990664 1.045883 0.3412187 1.156644 0.3412187 1.460565 0.2528128 1.460565 0.2140728 1.373903 0.2140727 1.463422 0.1205881 1.428085 0.1205881 1.428085 0.1316481 1.272555 0.2528129 1.188231 0.252813 1.188232 0.28561 1.945016 0.6148759 1.920101 0.6148759 1.920101 0.7424094 1.475616 0.4326248 1.432625 0.4326248 1.432625 0.4419285 1.179276 0.28561 1.179276 0.2528129 1.053018 0.2528129 1.044068 0.3329567 1.044068 0.3205851 1.000488 0.3205851 1.295579 0.252813 1.272555 0.2528129 1.272555 0.2856099 1.272555 0.2528129 1.295579 0.252813 1.295579 0.2140727 1.454137 0.9357835 1.454137 0.9265977 1.449634 0.9265977 1.577549 0.9265977 1.565234 0.9265977 1.565234 0.9357835 1.456524 0.9155978 1.444498 0.9155978 1.444498 0.9247831 1.40003 0.9357835 1.40003 0.9265977 1.379746 0.9265977 1.047357 0.01762789 1.045888 0.07377058 1.051834 0.06548821 1.152293 0.02071493 1.145941 0.02213335 1.14598 0.04982274 1.071551 0.05187094 1.06636 0.04771524 1.06206 0.053842 1.103204 4.88464e-4 1.067514 8.04474e-4 1.068279 0.006764054 1.127641 0.1844576 1.101071 0.1844576 1.101071 0.1931164 1.064468 0.04335635 1.064993 0.02227306 1.059615 0.0207507 1.123577 0.06251293 1.102368 0.06344956 1.102103 0.08445197 1.527945 0.9265979 1.523443 0.9265977 1.523443 0.9357835 1.541137 0.9247834 1.541136 0.9155978 1.505697 0.9155978 1.523443 0.9265977 1.48879 0.9265977 1.48879 0.9357835 1.045883 0.2023016 1.07353 0.2023016 1.07353 0.1931163 1.444498 0.9155978 1.389918 0.9155975 1.389918 0.9247831 1.566898 0.9247831 1.566897 0.9155978 1.554871 0.9155978 1.053269 0.01916384 1.051834 0.06548821 1.058948 0.04857367 1.140609 0.0445531 1.14598 0.04982274 1.145941 0.02213335 1.045883 0.1844576 1.045883 0.193116 1.07353 0.1931163 1.295579 0.205219 1.295579 0.2140727 1.318602 0.2140727 1.318602 0.3329197 1.295579 0.3329195 1.295579 0.3452492 1.884241 0.9410114 1.862386 0.9410116 1.862386 0.952134 1.920263 0.223552 1.920101 0.2327558 1.957133 0.2327558 1.364925 0.2944475 1.318602 0.2944474 1.318602 0.3205383 1.920101 0.2327558 1.920101 0.3202334 1.957133 0.3202335 1.157729 0.907238 1.157729 0.9326534 1.166933 0.9326535 1.000488 0.3452001 1.044068 0.3452001 1.044068 0.3329567 1.042641 0.9326536 1.042641 0.9072379 1.000488 0.92285 1.728519 0.6419227 1.728519 0.6065858 1.718715 0.6065858 1.053018 0.2528129 1.179276 0.2528129 1.179276 0.2140728 1.051845 0.9326536 1.051844 0.9072378 1.042641 0.9072379 1.000488 0.28561 1.000488 0.2944943 1.044068 0.2944945 1.373903 0.28561 1.373903 0.2528129 1.364925 0.252813 1.373903 0.28561 1.460565 0.2856102 1.460565 0.2528128 1.469512 0.2528128 1.460565 0.2528128 1.460565 0.2856102 1.460565 0.2140728 1.460565 0.2528128 1.469512 0.2528128 1.000488 0.2140725 1.044068 0.2140728 1.044068 0.2051816 1.505545 0.2856101 1.469512 0.2856102 1.469512 0.2944943 1.156644 0.2990664 1.153734 0.2903351 1.048793 0.2903351 1.553072 0.9265979 1.530928 0.9265979 1.530928 0.9357835 1.565234 0.9265977 1.558196 0.9265977 1.558196 0.9357835 1.530928 0.9265979 1.527945 0.9265979 1.527945 0.9357835 1.057892 0.01086807 1.053874 0.006297409 1.047357 0.01762789 1.045883 0.09480309 1.045883 0.1021202 1.055068 0.1021202 1.068732 0.05807965 1.062461 0.08306509 1.07595 0.08376377 1.128612 0.1931164 1.128612 0.2023019 1.15626 0.2023016 1.419383 0.9357835 1.419383 0.9265977 1.412345 0.9265977 1.621477 0.9247831 1.621477 0.9155975 1.566897 0.9155978 1.412345 0.9357835 1.412345 0.9265977 1.40003 0.9265977 1.505697 0.9155978 1.470259 0.9155978 1.470259 0.9247834 1.295579 4.88289e-4 1.272555 4.88297e-4 1.272555 0.2052192 1.318602 0.2944474 1.295579 0.2944474 1.295579 0.3205384 1.272555 0.3329195 1.272555 0.3452491 1.295579 0.3452492 1.318602 0.3205383 1.295579 0.3205384 1.295579 0.3329195 1.272555 0.3205384 1.272555 0.3329195 1.295579 0.3329195 1.945016 0.5964685 1.945016 0.5543156 1.920101 0.570132 1.906096 0.9521344 1.906096 0.9410116 1.884241 0.9410114 1.791454 0.9521344 1.862386 0.952134 1.862386 0.9410116 1.469512 0.3452002 1.505545 0.3452002 1.505545 0.3329566 1.884065 0.2143492 1.883715 0.2235527 1.918286 0.2235528 1.883715 0.2235527 1.883598 0.2327569 1.918287 0.2327569 1.957133 0.3294374 1.920264 0.3294375 1.920751 0.3386411 1.957133 0.3202335 1.920101 0.3202334 1.920264 0.3294375 1.272555 0.3452491 1.272555 0.3329195 1.188232 0.3329193 1.945016 0.7608169 1.945016 0.7516131 1.920101 0.7516131 1.08002 0.04160183 1.08002 0.05257523 1.123011 0.05257523 1.945016 0.6148759 1.945016 0.6056721 1.920101 0.6056721 1.920752 0.2143484 1.920263 0.223552 1.957133 0.2235522 1.061048 0.9326534 1.061048 0.9072378 1.051844 0.9072378 1.148526 0.9326536 1.157729 0.9326534 1.157729 0.907238 1.000488 0.3205851 1.044068 0.3205851 1.044068 0.2944945 1.044068 6.73867e-4 1.000488 6.73875e-4 1.000488 0.2051817 1.364925 0.252813 1.373903 0.2528129 1.373903 0.2140727 1.730731 0.9391972 1.944592 0.9391971 1.944592 0.8284353 1.000488 0.2528129 1.000488 0.28561 1.044068 0.28561 1.945016 0.7516131 1.945016 0.7424094 1.920101 0.7424094 1.883598 0.2327569 1.883598 0.36029 1.918286 0.36029 1.710524 0.4326251 1.626433 0.4326247 1.626433 0.4419283 1.505545 0.3329566 1.505545 0.3205853 1.469512 0.3205853 1.044068 0.2528129 1.053018 0.2528129 1.053018 0.2140728 1.179276 0.2140728 1.179276 0.2528129 1.188231 0.252813 1.318602 0.2856103 1.295579 0.2856099 1.295579 0.2944474 1.318602 0.2528129 1.295579 0.252813 1.295579 0.2856099 1.364925 0.2944475 1.364925 0.28561 1.318602 0.2856103 1.364925 0.252813 1.318602 0.2528129 1.318602 0.2856103 1.272555 0.2140727 1.272555 0.2052192 1.188232 0.2052192 1.295579 0.2140727 1.295579 0.252813 1.318602 0.2528129 1.272555 0.2140727 1.188232 0.2140728 1.188231 0.252813 1.318602 0.2052192 1.318603 4.88513e-4 1.295579 4.88289e-4 1.364925 0.2052192 1.364925 4.88281e-4 1.318603 4.88513e-4 1.505545 0.2528129 1.505545 0.2140728 1.469512 0.2140727 1.505545 0.2140728 1.505545 0.2051752 1.469512 0.2051753 1.469512 5.12323e-4 1.469512 0.2051753 1.505545 0.2051752 1.505545 0.2528129 1.469512 0.2528128 1.469512 0.2856102 1.730967 0.3348015 1.730967 0.5486626 1.881784 0.5486628 1.000488 0.2528129 1.044068 0.2528129 1.044068 0.2140728 1.730967 0.5486626 1.733877 0.5573942 1.878873 0.5573942 1.721999 0.831346 1.721999 0.9362868 1.730731 0.9391972 1.14343 0.01716881 1.147923 0.01234704 1.137722 0.007961034 1.152668 0.06678771 1.142777 0.05496656 1.136054 0.05899429 1.136949 0.01433765 1.137722 0.007961034 1.103101 0.006463944 1.152293 0.02071493 1.147923 0.01234704 1.14343 0.01716881 1.12823 0.0844019 1.141682 0.0840274 1.136054 0.05899429 1.446652 0.9357835 1.446652 0.9265977 1.424507 0.9265977 1.101071 0.1931164 1.101071 0.2023019 1.128612 0.2023019 1.07353 0.2023016 1.101071 0.2023019 1.101071 0.1931164 1.449634 0.9357835 1.449634 0.9265977 1.446652 0.9265977 1.554871 0.9247831 1.554871 0.9155978 1.541136 0.9155978 1.12823 0.0844019 1.102103 0.08445197 1.102014 0.09187269 1.102368 0.06344956 1.123577 0.06251293 1.122161 0.05621325 1.139571 0.02124476 1.14343 0.01716881 1.136949 0.01433765 1.067514 8.04474e-4 1.053874 0.006297409 1.057892 0.01086807 1.133425 0.0527479 1.136054 0.05899429 1.142777 0.05496656 1.13594 0.01979029 1.136949 0.01433765 1.102993 0.01307231 1.137722 0.007961034 1.138676 0.00206077 1.103204 4.88464e-4 1.145941 0.02213335 1.14343 0.01716881 1.139571 0.02124476 1.071551 0.05187094 1.068732 0.05807965 1.081175 0.06195604 1.15626 0.1844575 1.127641 0.1844576 1.128612 0.1931164 1.081175 0.06195604 1.07595 0.08376377 1.102103 0.08445197 1.138665 0.04879873 1.142777 0.05496656 1.14598 0.04982274 1.068847 0.01318633 1.102993 0.01307231 1.103101 0.006463944 1.48879 0.9357835 1.48879 0.9265977 1.454137 0.9265977 1.12989 0.1608373 1.125262 0.1680715 1.139076 0.1680715 1.149798 0.1758696 1.15626 0.1758696 1.15626 0.1666837 1.621477 0.9247831 1.631649 0.9247834 1.631649 0.9155975 1.07595 0.08376377 1.074652 0.0912249 1.102014 0.09187269 1.102368 0.06344956 1.102452 0.05688887 1.082787 0.05568909 1.059615 0.0207507 1.064993 0.02227306 1.066018 0.02002781 1.138676 0.00206077 1.137722 0.007961034 1.147923 0.01234704 1.06636 0.04771524 1.064468 0.04335635 1.058948 0.04857367 1.069677 0.01867198 1.102902 0.01896369 1.102993 0.01307231 1.074501 0.1844576 1.07353 0.1931163 1.101071 0.1931164 1.364925 0.3329192 1.318602 0.3329197 1.318602 0.3452491 1.918286 0.36029 1.883598 0.36029 1.883715 0.3694932 1.295579 0.2856099 1.272555 0.2856099 1.272555 0.2944474 1.906096 0.9410116 1.906096 0.9521344 1.942511 0.9521344 1.188232 0.3205384 1.272555 0.3205384 1.272555 0.2944474 1.318602 0.3329197 1.364925 0.3329192 1.364925 0.3205381 1.061048 0.9072378 1.061048 0.9326534 1.148526 0.9326536 1.920101 0.7871531 1.945016 0.8029695 1.945016 0.7608169 1.870277 0.7697482 1.71946 0.769748 1.71946 0.8119004 1.209085 0.9228498 1.166933 0.9072378 1.166933 0.9326535 1.188231 0.252813 1.179276 0.2528129 1.179276 0.28561 1.053018 0.28561 1.053018 0.2528129 1.044068 0.2528129 1.272555 0.2856099 1.188232 0.28561 1.188232 0.2944475 1.945016 0.6056721 1.945016 0.5964685 1.920101 0.5964685 1.364925 0.2052192 1.318602 0.2052192 1.318602 0.2140727 1.318602 0.2140727 1.318602 0.2528129 1.364925 0.252813 1.272555 0.2140727 1.295579 0.2140727 1.295579 0.205219 1.272555 4.88297e-4 1.188232 4.88337e-4 1.188232 0.2052192 1.272555 0.3329195 1.272555 0.3205384 1.188232 0.3205384 1.469512 0.3205853 1.505545 0.3205853 1.505545 0.2944943 1.867367 0.7610166 1.722371 0.7610161 1.71946 0.769748 1.062268 0.01583838 1.068847 0.01318633 1.068279 0.006764054 1.068732 0.05807965 1.06206 0.053842 1.051834 0.06548821 1.053269 0.01916384 1.059615 0.0207507 1.062268 0.01583838 1.424507 0.9357835 1.424507 0.9265977 1.419383 0.9265977 1.558196 0.9265977 1.553072 0.9265979 1.553072 0.9357835 1.389918 0.9247831 1.389918 0.9155975 1.379746 0.9155975 1.147923 0.01234704 1.152293 0.02071493 1.158206 0.01933556 1.139076 0.1680715 1.125262 0.1680715 1.12989 0.1753889 1.597833 0.9265977 1.577549 0.9265977 1.577549 0.9357835 1.470259 0.9155978 1.456524 0.9155978 1.456524 0.9247831 1.045883 0.09480309 1.059697 0.09480309 1.055069 0.08756864 1.052344 0.1758695 1.052344 0.1666837 1.045883 0.1666837 1.066018 0.02002781 1.069677 0.01867198 1.068847 0.01318633 1.123577 0.06251293 1.136054 0.05899429 1.133425 0.0527479 1.295579 0.2944474 1.272555 0.2944474 1.272555 0.3205384 1.158206 0.01933556 1.152293 0.02071493 1.152668 0.06678771 1.918286 0.3694939 1.883715 0.3694932 1.884066 0.3786978 1.045883 0.2990664 1.045883 0.3412187 1.156644 0.3412187 1.460565 0.2528128 1.460565 0.2140728 1.373903 0.2140727 1.463422 0.1205881 1.428085 0.1205881 1.428085 0.1316481 1.272555 0.2528129 1.188231 0.252813 1.188232 0.28561 1.945016 0.6148759 1.920101 0.6148759 1.920101 0.7424094 1.475616 0.4326248 1.432625 0.4326248 1.432625 0.4419285 1.179276 0.28561 1.179276 0.2528129 1.053018 0.2528129 1.044068 0.3329567 1.044068 0.3205851 1.000488 0.3205851 1.295579 0.252813 1.272555 0.2528129 1.272555 0.2856099 1.272555 0.2528129 1.295579 0.252813 1.295579 0.2140727 1.454137 0.9357835 1.454137 0.9265977 1.449634 0.9265977 1.577549 0.9265977 1.565234 0.9265977 1.565234 0.9357835 1.456524 0.9155978 1.444498 0.9155978 1.444498 0.9247831 1.40003 0.9357835 1.40003 0.9265977 1.379746 0.9265977 1.047357 0.01762789 1.045888 0.07377058 1.051834 0.06548821 1.152293 0.02071493 1.145941 0.02213335 1.14598 0.04982274 1.071551 0.05187094 1.06636 0.04771524 1.06206 0.053842 1.103204 4.88464e-4 1.067514 8.04474e-4 1.068279 0.006764054 1.127641 0.1844576 1.101071 0.1844576 1.101071 0.1931164 1.064468 0.04335635 1.064993 0.02227306 1.059615 0.0207507 1.123577 0.06251293 1.102368 0.06344956 1.102103 0.08445197 1.527945 0.9265979 1.523443 0.9265977 1.523443 0.9357835 1.541137 0.9247834 1.541136 0.9155978 1.505697 0.9155978 1.523443 0.9265977 1.48879 0.9265977 1.48879 0.9357835 1.045883 0.2023016 1.07353 0.2023016 1.07353 0.1931163 1.444498 0.9155978 1.389918 0.9155975 1.389918 0.9247831 1.566898 0.9247831 1.566897 0.9155978 1.554871 0.9155978 1.053269 0.01916384 1.051834 0.06548821 1.058948 0.04857367 1.140609 0.0445531 1.14598 0.04982274 1.145941 0.02213335 1.045883 0.1844576 1.045883 0.193116 1.07353 0.1931163 1.295579 0.205219 1.295579 0.2140727 1.318602 0.2140727 1.318602 0.3329197 1.295579 0.3329195 1.295579 0.3452492 1.884241 0.9410114 1.862386 0.9410116 1.862386 0.952134 1.920263 0.223552 1.920101 0.2327558 1.957133 0.2327558 1.364925 0.2944475 1.318602 0.2944474 1.318602 0.3205383 1.920101 0.2327558 1.920101 0.3202334 1.957133 0.3202335 1.157729 0.907238 1.157729 0.9326534 1.166933 0.9326535 1.000488 0.3452001 1.044068 0.3452001 1.044068 0.3329567 1.042641 0.9326536 1.042641 0.9072379 1.000488 0.92285 1.728519 0.6419227 1.728519 0.6065858 1.718715 0.6065858 1.053018 0.2528129 1.179276 0.2528129 1.179276 0.2140728 1.051845 0.9326536 1.051844 0.9072378 1.042641 0.9072379 1.000488 0.28561 1.000488 0.2944943 1.044068 0.2944945 1.373903 0.28561 1.373903 0.2528129 1.364925 0.252813 1.373903 0.28561 1.460565 0.2856102 1.460565 0.2528128 1.469512 0.2528128 1.460565 0.2528128 1.460565 0.2856102 1.460565 0.2140728 1.460565 0.2528128 1.469512 0.2528128 1.000488 0.2140725 1.044068 0.2140728 1.044068 0.2051816 1.505545 0.2856101 1.469512 0.2856102 1.469512 0.2944943 1.153734 0.2903351 1.048793 0.2903351 1.045883 0.2990664 1.553072 0.9265979 1.530928 0.9265979 1.530928 0.9357835 1.565234 0.9265977 1.558196 0.9265977 1.558196 0.9357835 1.530928 0.9265979 1.527945 0.9265979 1.527945 0.9357835 1.057892 0.01086807 1.053874 0.006297409 1.047357 0.01762789 1.045883 0.09480309 1.045883 0.1021202 1.055068 0.1021202 1.068732 0.05807965 1.062461 0.08306509 1.07595 0.08376377 1.128612 0.1931164 1.128612 0.2023019 1.15626 0.2023016 1.419383 0.9357835 1.419383 0.9265977 1.412345 0.9265977 1.621477 0.9247831 1.621477 0.9155975 1.566897 0.9155978 1.412345 0.9357835 1.412345 0.9265977 1.40003 0.9265977 1.505697 0.9155978 1.470259 0.9155978 1.470259 0.9247834 1.295579 4.88289e-4 1.272555 4.88297e-4 1.272555 0.2052192 1.318602 0.2944474 1.295579 0.2944474 1.295579 0.3205384 1.272555 0.3329195 1.272555 0.3452491 1.295579 0.3452492 1.318602 0.3205383 1.295579 0.3205384 1.295579 0.3329195 1.272555 0.3205384 1.272555 0.3329195 1.295579 0.3329195 1.945016 0.5964685 1.945016 0.5543156 1.920101 0.570132 1.906096 0.9521344 1.906096 0.9410116 1.884241 0.9410114 1.791454 0.9521344 1.862386 0.952134 1.862386 0.9410116 1.469512 0.3452002 1.505545 0.3452002 1.505545 0.3329566 1.884065 0.2143492 1.883715 0.2235527 1.918286 0.2235528 1.883715 0.2235527 1.883598 0.2327569 1.918287 0.2327569 1.957133 0.3294374 1.920264 0.3294375 1.920751 0.3386411 1.957133 0.3202335 1.920101 0.3202334 1.920264 0.3294375 1.272555 0.3452491 1.272555 0.3329195 1.188232 0.3329193 1.945016 0.7608169 1.945016 0.7516131 1.920101 0.7516131 1.08002 0.04160183 1.08002 0.05257523 1.123011 0.05257523 1.945016 0.6148759 1.945016 0.6056721 1.920101 0.6056721 1.920752 0.2143484 1.920263 0.223552 1.957133 0.2235522 1.061048 0.9326534 1.061048 0.9072378 1.051844 0.9072378 1.148526 0.9326536 1.157729 0.9326534 1.157729 0.907238 1.000488 0.3205851 1.044068 0.3205851 1.044068 0.2944945 1.044068 6.73867e-4 1.000488 6.73875e-4 1.000488 0.2051817 1.364925 0.252813 1.373903 0.2528129 1.373903 0.2140727 1.730731 0.9391972 1.944592 0.9391971 1.944592 0.8284353 1.000488 0.2528129 1.000488 0.28561 1.044068 0.28561 1.945016 0.7516131 1.945016 0.7424094 1.920101 0.7424094 1.883598 0.2327569 1.883598 0.36029 1.918286 0.36029 1.710524 0.4326251 1.626433 0.4326247 1.626433 0.4419283 1.505545 0.3329566 1.505545 0.3205853 1.469512 0.3205853 1.044068 0.2528129 1.053018 0.2528129 1.053018 0.2140728 1.179276 0.2140728 1.179276 0.2528129 1.188231 0.252813 1.318602 0.2856103 1.295579 0.2856099 1.295579 0.2944474 1.318602 0.2528129 1.295579 0.252813 1.295579 0.2856099 1.364925 0.2944475 1.364925 0.28561 1.318602 0.2856103 1.364925 0.252813 1.318602 0.2528129 1.318602 0.2856103 1.272555 0.2140727 1.272555 0.2052192 1.188232 0.2052192 1.295579 0.2140727 1.295579 0.252813 1.318602 0.2528129 1.272555 0.2140727 1.188232 0.2140728 1.188231 0.252813 1.318602 0.2052192 1.318603 4.88513e-4 1.295579 4.88289e-4 1.364925 0.2052192 1.364925 4.88281e-4 1.318603 4.88513e-4 1.505545 0.2528129 1.505545 0.2140728 1.469512 0.2140727 1.505545 0.2140728 1.505545 0.2051752 1.469512 0.2051753 1.469512 5.12323e-4 1.469512 0.2051753 1.505545 0.2051752 1.505545 0.2528129 1.469512 0.2528128 1.469512 0.2856102 1.730967 0.3348015 1.730967 0.5486626 1.881784 0.5486628 1.000488 0.2528129 1.044068 0.2528129 1.044068 0.2140728 1.730967 0.5486626 1.733877 0.5573942 1.878873 0.5573942 1.721999 0.831346 1.721999 0.9362868 1.730731 0.9391972 1.14343 0.01716881 1.147923 0.01234704 1.137722 0.007961034 1.152668 0.06678771 1.142777 0.05496656 1.136054 0.05899429 1.136949 0.01433765 1.137722 0.007961034 1.103101 0.006463944 1.152293 0.02071493 1.147923 0.01234704 1.14343 0.01716881 1.12823 0.0844019 1.141682 0.0840274 1.136054 0.05899429 1.446652 0.9357835 1.446652 0.9265977 1.424507 0.9265977 1.101071 0.1931164 1.101071 0.2023019 1.128612 0.2023019 1.07353 0.2023016 1.101071 0.2023019 1.101071 0.1931164 1.449634 0.9357835 1.449634 0.9265977 1.446652 0.9265977 1.554871 0.9247831 1.554871 0.9155978 1.541136 0.9155978 1.12823 0.0844019 1.102103 0.08445197 1.102014 0.09187269 1.102368 0.06344956 1.123577 0.06251293 1.122161 0.05621325 1.139571 0.02124476 1.14343 0.01716881 1.136949 0.01433765 1.067514 8.04474e-4 1.053874 0.006297409 1.057892 0.01086807 1.133425 0.0527479 1.136054 0.05899429 1.142777 0.05496656 1.13594 0.01979029 1.136949 0.01433765 1.102993 0.01307231 1.137722 0.007961034 1.138676 0.00206077 1.103204 4.88464e-4 1.145941 0.02213335 1.14343 0.01716881 1.139571 0.02124476 1.071551 0.05187094 1.068732 0.05807965 1.081175 0.06195604 1.15626 0.1844575 1.127641 0.1844576 1.128612 0.1931164 1.081175 0.06195604 1.07595 0.08376377 1.102103 0.08445197 1.138665 0.04879873 1.142777 0.05496656 1.14598 0.04982274 1.068847 0.01318633 1.102993 0.01307231 1.103101 0.006463944 1.48879 0.9357835 1.48879 0.9265977 1.454137 0.9265977 1.12989 0.1608373 1.125262 0.1680715 1.139076 0.1680715 1.149798 0.1758696 1.15626 0.1758696 1.15626 0.1666837 1.621477 0.9247831 1.631649 0.9247834 1.631649 0.9155975 1.07595 0.08376377 1.074652 0.0912249 1.102014 0.09187269 1.102368 0.06344956 1.102452 0.05688887 1.082787 0.05568909 1.059615 0.0207507 1.064993 0.02227306 1.066018 0.02002781 1.138676 0.00206077 1.137722 0.007961034 1.147923 0.01234704 1.06636 0.04771524 1.064468 0.04335635 1.058948 0.04857367 1.069677 0.01867198 1.102902 0.01896369 1.102993 0.01307231 1.074501 0.1844576 1.07353 0.1931163 1.101071 0.1931164 1.364925 0.3329192 1.318602 0.3329197 1.318602 0.3452491 1.918286 0.36029 1.883598 0.36029 1.883715 0.3694932 1.295579 0.2856099 1.272555 0.2856099 1.272555 0.2944474 1.906096 0.9410116 1.906096 0.9521344 1.942511 0.9521344 1.188232 0.3205384 1.272555 0.3205384 1.272555 0.2944474 1.318602 0.3329197 1.364925 0.3329192 1.364925 0.3205381 1.061048 0.9072378 1.061048 0.9326534 1.148526 0.9326536 1.920101 0.7871531 1.945016 0.8029695 1.945016 0.7608169 1.870277 0.7697482 1.71946 0.769748 1.71946 0.8119004 1.209085 0.9228498 1.166933 0.9072378 1.166933 0.9326535 1.188231 0.252813 1.179276 0.2528129 1.179276 0.28561 1.053018 0.28561 1.053018 0.2528129 1.044068 0.2528129 1.272555 0.2856099 1.188232 0.28561 1.188232 0.2944475 1.945016 0.6056721 1.945016 0.5964685 1.920101 0.5964685 1.364925 0.2052192 1.318602 0.2052192 1.318602 0.2140727 1.318602 0.2140727 1.318602 0.2528129 1.364925 0.252813 1.272555 0.2140727 1.295579 0.2140727 1.295579 0.205219 1.272555 4.88297e-4 1.188232 4.88337e-4 1.188232 0.2052192 1.272555 0.3329195 1.272555 0.3205384 1.188232 0.3205384 1.469512 0.3205853 1.505545 0.3205853 1.505545 0.2944943 1.867367 0.7610166 1.722371 0.7610161 1.71946 0.769748 1.062268 0.01583838 1.068847 0.01318633 1.068279 0.006764054 1.068732 0.05807965 1.06206 0.053842 1.051834 0.06548821 1.053269 0.01916384 1.059615 0.0207507 1.062268 0.01583838 1.424507 0.9357835 1.424507 0.9265977 1.419383 0.9265977 1.558196 0.9265977 1.553072 0.9265979 1.553072 0.9357835 1.389918 0.9247831 1.389918 0.9155975 1.379746 0.9155975 1.147923 0.01234704 1.152293 0.02071493 1.158206 0.01933556 1.139076 0.1680715 1.125262 0.1680715 1.12989 0.1753889 1.597833 0.9265977 1.577549 0.9265977 1.577549 0.9357835 1.470259 0.9155978 1.456524 0.9155978 1.456524 0.9247831 1.045883 0.09480309 1.059697 0.09480309 1.055069 0.08756864 1.052344 0.1758695 1.052344 0.1666837 1.045883 0.1666837 1.066018 0.02002781 1.069677 0.01867198 1.068847 0.01318633 1.123577 0.06251293 1.136054 0.05899429 1.133425 0.0527479 1.295579 0.2944474 1.272555 0.2944474 1.272555 0.3205384 1.158206 0.01933556 1.152293 0.02071493 1.152668 0.06678771 1.918286 0.3694939 1.918286 0.3786976 1.884066 0.3786978 1.156644 0.3412187 1.045883 0.3412187 1.045883 0.2990664 1.460565 0.2528128 1.373903 0.2528129 1.373903 0.2140727 1.428085 0.1316481 1.428085 0.1205881 1.463422 0.1205881 1.272555 0.2528129 1.272555 0.2856099 1.188232 0.28561 1.920101 0.7424094 1.920101 0.6148759 1.945016 0.6148759 1.432625 0.4419285 1.432625 0.4326248 1.475616 0.4326248 1.179276 0.28561 1.053018 0.28561 1.053018 0.2528129 1.000488 0.3205851 1.044068 0.3205851 1.044068 0.3329567 1.272555 0.2856099 1.272555 0.2528129 1.295579 0.252813 1.272555 0.2528129 1.272555 0.2140727 1.295579 0.2140727 1.449634 0.9265977 1.454137 0.9265977 1.454137 0.9357835 1.565234 0.9357835 1.565234 0.9265977 1.577549 0.9265977 1.444498 0.9247831 1.444498 0.9155978 1.456524 0.9155978 1.379746 0.9265977 1.40003 0.9265977 1.40003 0.9357835 1.047357 0.01762789 1.053269 0.01916384 1.051834 0.06548821 1.152293 0.02071493 1.152668 0.06678771 1.14598 0.04982274 1.071551 0.05187094 1.068732 0.05807965 1.06206 0.053842 1.068279 0.006764054 1.067514 8.04474e-4 1.103204 4.88464e-4 1.127641 0.1844576 1.128612 0.1931164 1.101071 0.1931164 1.064468 0.04335635 1.058948 0.04857367 1.059615 0.0207507 1.123577 0.06251293 1.12823 0.0844019 1.102103 0.08445197 1.523443 0.9357835 1.523443 0.9265977 1.527945 0.9265979 1.505697 0.9155978 1.541136 0.9155978 1.541137 0.9247834 1.48879 0.9357835 1.48879 0.9265977 1.523443 0.9265977 1.07353 0.1931163 1.07353 0.2023016 1.045883 0.2023016 1.389918 0.9247831 1.389918 0.9155975 1.444498 0.9155978 1.554871 0.9155978 1.566897 0.9155978 1.566898 0.9247831 1.053269 0.01916384 1.059615 0.0207507 1.058948 0.04857367 1.140609 0.0445531 1.14054 0.0235123 1.145941 0.02213335 1.045883 0.1844576 1.074501 0.1844576 1.07353 0.1931163 1.295579 0.205219 1.318602 0.2052192 1.318602 0.2140727 1.318602 0.3329197 1.318602 0.3452491 1.295579 0.3452492 1.884241 0.9410114 1.884241 0.9521344 1.862386 0.952134 1.920263 0.223552 1.957133 0.2235522 1.957133 0.2327558 1.318602 0.3205383 1.318602 0.2944474 1.364925 0.2944475 1.957133 0.3202335 1.920101 0.3202334 1.920101 0.2327558 1.157729 0.907238 1.166933 0.9072378 1.166933 0.9326535 1.044068 0.3329567 1.044068 0.3452001 1.000488 0.3452001 1.042641 0.9326536 1.000488 0.9326536 1.000488 0.92285 1.728519 0.6419227 1.710385 0.6419227 1.718715 0.6065858 1.053018 0.2528129 1.053018 0.2140728 1.179276 0.2140728 1.042641 0.9072379 1.051844 0.9072378 1.051845 0.9326536 1.000488 0.28561 1.044068 0.28561 1.044068 0.2944945 1.364925 0.252813 1.373903 0.2528129 1.373903 0.28561 1.373903 0.28561 1.373903 0.2528129 1.460565 0.2528128 1.469512 0.2528128 1.469512 0.2856102 1.460565 0.2856102 1.460565 0.2140728 1.469512 0.2140727 1.469512 0.2528128 1.044068 0.2051816 1.044068 0.2140728 1.000488 0.2140725 1.469512 0.2944943 1.469512 0.2856102 1.505545 0.2856101 1.156644 0.2990664 1.045883 0.2990664 1.048793 0.2903351 1.530928 0.9357835 1.530928 0.9265979 1.553072 0.9265979 1.558196 0.9357835 1.558196 0.9265977 1.565234 0.9265977 1.527945 0.9357835 1.527945 0.9265979 1.530928 0.9265979 1.057892 0.01086807 1.053269 0.01916384 1.047357 0.01762789 1.045883 0.09480309 1.059697 0.09480309 1.055068 0.1021202 1.07595 0.08376377 1.062461 0.08306509 1.068732 0.05807965 1.15626 0.2023016 1.128612 0.2023019 1.128612 0.1931164 1.412345 0.9265977 1.419383 0.9265977 1.419383 0.9357835 1.566897 0.9155978 1.621477 0.9155975 1.621477 0.9247831 1.40003 0.9265977 1.412345 0.9265977 1.412345 0.9357835 1.470259 0.9247834 1.470259 0.9155978 1.505697 0.9155978 1.295579 4.88289e-4 1.295579 0.205219 1.272555 0.2052192 1.295579 0.3205384 1.295579 0.2944474 1.318602 0.2944474 1.295579 0.3452492 1.272555 0.3452491 1.272555 0.3329195 1.318602 0.3205383 1.318602 0.3329197 1.295579 0.3329195 1.295579 0.3329195 1.272555 0.3329195 1.272555 0.3205384 1.945016 0.5964685 1.920101 0.5964685 1.920101 0.570132 1.906096 0.9521344 1.884241 0.9521344 1.884241 0.9410114 1.791454 0.9521344 1.791454 0.9410114 1.862386 0.9410116 1.469512 0.3452002 1.469512 0.3329566 1.505545 0.3329566 1.884065 0.2143492 1.918287 0.2143492 1.918286 0.2235528 1.883715 0.2235527 1.918286 0.2235528 1.918287 0.2327569 1.957133 0.3294374 1.957133 0.3386409 1.920751 0.3386411 1.957133 0.3202335 1.957133 0.3294374 1.920264 0.3294375 1.272555 0.3452491 1.188232 0.3452492 1.188232 0.3329193 1.920101 0.7516131 1.945016 0.7516131 1.945016 0.7608169 1.123011 0.05257523 1.08002 0.05257523 1.08002 0.04160183 1.945016 0.6148759 1.920101 0.6148759 1.920101 0.6056721 1.920752 0.2143484 1.957133 0.2143483 1.957133 0.2235522 1.051844 0.9072378 1.061048 0.9072378 1.061048 0.9326534 1.148526 0.9326536 1.148526 0.9072379 1.157729 0.907238 1.044068 0.2944945 1.044068 0.3205851 1.000488 0.3205851 1.000488 0.2051817 1.000488 6.73875e-4 1.044068 6.73867e-4 1.364925 0.252813 1.364925 0.2140727 1.373903 0.2140727 1.944592 0.8284353 1.944592 0.9391971 1.730731 0.9391972 1.000488 0.2528129 1.044068 0.2528129 1.044068 0.28561 1.945016 0.7516131 1.920101 0.7516131 1.920101 0.7424094 1.918286 0.36029 1.883598 0.36029 1.883598 0.2327569 1.710524 0.4326251 1.718715 0.4958242 1.626433 0.4419283 1.469512 0.3205853 1.505545 0.3205853 1.505545 0.3329566 1.044068 0.2528129 1.044068 0.2140728 1.053018 0.2140728 1.179276 0.2140728 1.188232 0.2140728 1.188231 0.252813 1.295579 0.2944474 1.295579 0.2856099 1.318602 0.2856103 1.295579 0.2856099 1.295579 0.252813 1.318602 0.2528129 1.364925 0.2944475 1.318602 0.2944474 1.318602 0.2856103 1.318602 0.2856103 1.318602 0.2528129 1.364925 0.252813 1.272555 0.2140727 1.188232 0.2140728 1.188232 0.2052192 1.295579 0.2140727 1.318602 0.2140727 1.318602 0.2528129 1.188231 0.252813 1.188232 0.2140728 1.272555 0.2140727 1.318602 0.2052192 1.295579 0.205219 1.295579 4.88289e-4 1.364925 0.2052192 1.318602 0.2052192 1.318603 4.88513e-4 1.469512 0.2140727 1.505545 0.2140728 1.505545 0.2528129 1.505545 0.2140728 1.469512 0.2140727 1.469512 0.2051753 1.505545 0.2051752 1.469512 0.2051753 1.469512 5.12323e-4 1.505545 0.2528129 1.505545 0.2856101 1.469512 0.2856102 1.881784 0.5486628 1.730967 0.5486626 1.730967 0.3348015 1.000488 0.2528129 1.000488 0.2140725 1.044068 0.2140728 1.730967 0.5486626 1.881784 0.5486628 1.878873 0.5573942 1.730731 0.9391972 1.721999 0.9362868 1.721999 0.831346 1.14343 0.01716881 1.136949 0.01433765 1.137722 0.007961034 1.152668 0.06678771 1.14918 0.07562226 1.136054 0.05899429 1.136949 0.01433765 1.102993 0.01307231 1.103101 0.006463944 1.152293 0.02071493 1.145941 0.02213335 1.14343 0.01716881 1.136054 0.05899429 1.141682 0.0840274 1.12823 0.0844019 1.424507 0.9265977 1.446652 0.9265977 1.446652 0.9357835 1.128612 0.2023019 1.101071 0.2023019 1.101071 0.1931164 1.101071 0.1931164 1.101071 0.2023019 1.07353 0.2023016 1.446652 0.9265977 1.449634 0.9265977 1.449634 0.9357835 1.541136 0.9155978 1.554871 0.9155978 1.554871 0.9247831 1.12823 0.0844019 1.129347 0.09187269 1.102014 0.09187269 1.102368 0.06344956 1.102452 0.05688887 1.122161 0.05621325 1.139571 0.02124476 1.13594 0.01979029 1.136949 0.01433765 1.067514 8.04474e-4 1.068279 0.006764054 1.057892 0.01086807 1.133425 0.0527479 1.138665 0.04879873 1.142777 0.05496656 1.13594 0.01979029 1.102902 0.01896369 1.102993 0.01307231 1.103204 4.88464e-4 1.138676 0.00206077 1.137722 0.007961034 1.145941 0.02213335 1.14054 0.0235123 1.139571 0.02124476 1.081175 0.06195604 1.068732 0.05807965 1.071551 0.05187094 1.15626 0.1844575 1.15626 0.1931163 1.128612 0.1931164 1.081175 0.06195604 1.102368 0.06344956 1.102103 0.08445197 1.138665 0.04879873 1.140609 0.0445531 1.14598 0.04982274 1.068847 0.01318633 1.068279 0.006764054 1.103101 0.006463944 1.454137 0.9265977 1.48879 0.9265977 1.48879 0.9357835 1.139076 0.1680715 1.125262 0.1680715 1.12989 0.1608373 1.149798 0.1758696 1.149798 0.1666839 1.15626 0.1666837 1.621477 0.9247831 1.621477 0.9155975 1.631649 0.9155975 1.07595 0.08376377 1.102103 0.08445197 1.102014 0.09187269 1.102368 0.06344956 1.081175 0.06195604 1.082787 0.05568909 1.059615 0.0207507 1.062268 0.01583838 1.066018 0.02002781 1.138676 0.00206077 1.152043 0.007921338 1.147923 0.01234704 1.06636 0.04771524 1.06206 0.053842 1.058948 0.04857367 1.069677 0.01867198 1.068847 0.01318633 1.102993 0.01307231 1.074501 0.1844576 1.101071 0.1844576 1.101071 0.1931164 1.364925 0.3329192 1.364925 0.3452492 1.318602 0.3452491 1.918286 0.36029 1.918286 0.3694939 1.883715 0.3694932 1.272555 0.2944474 1.272555 0.2856099 1.295579 0.2856099 1.906096 0.9410116 1.942511 0.9410114 1.942511 0.9521344 1.272555 0.2944474 1.272555 0.3205384 1.188232 0.3205384 1.318602 0.3329197 1.318602 0.3205383 1.364925 0.3205381 1.061048 0.9072378 1.148526 0.9072379 1.148526 0.9326536 1.920101 0.7871531 1.920101 0.7608169 1.945016 0.7608169 1.71946 0.8119004 1.71946 0.769748 1.870277 0.7697482 1.209085 0.9228498 1.209086 0.9326535 1.166933 0.9326535 1.188231 0.252813 1.188232 0.28561 1.179276 0.28561 1.053018 0.28561 1.044068 0.28561 1.044068 0.2528129 1.188232 0.2944475 1.188232 0.28561 1.272555 0.2856099 1.945016 0.6056721 1.920101 0.6056721 1.920101 0.5964685 1.364925 0.2052192 1.364925 0.2140727 1.318602 0.2140727 1.318602 0.2140727 1.364925 0.2140727 1.364925 0.252813 1.272555 0.2140727 1.272555 0.2052192 1.295579 0.205219 1.272555 4.88297e-4 1.272555 0.2052192 1.188232 0.2052192 1.272555 0.3329195 1.188232 0.3329193 1.188232 0.3205384 1.505545 0.2944943 1.505545 0.3205853 1.469512 0.3205853 1.71946 0.769748 1.722371 0.7610161 1.867367 0.7610166 1.062268 0.01583838 1.057892 0.01086807 1.068279 0.006764054 1.051834 0.06548821 1.06206 0.053842 1.068732 0.05807965 1.053269 0.01916384 1.057892 0.01086807 1.062268 0.01583838 1.419383 0.9265977 1.424507 0.9265977 1.424507 0.9357835 1.553072 0.9357835 1.553072 0.9265979 1.558196 0.9265977 1.389918 0.9247831 1.379746 0.9247834 1.379746 0.9155975 1.147923 0.01234704 1.152043 0.007921338 1.158206 0.01933556 1.139076 0.1680715 1.139076 0.1753889 1.12989 0.1753889 1.577549 0.9357835 1.577549 0.9265977 1.597833 0.9265977 1.456524 0.9247831 1.456524 0.9155978 1.470259 0.9155978 1.055069 0.08756864 1.059697 0.09480309 1.045883 0.09480309 1.052344 0.1758695 1.045883 0.1758695 1.045883 0.1666837 1.066018 0.02002781 1.062268 0.01583838 1.068847 0.01318633 1.133425 0.0527479 1.136054 0.05899429 1.123577 0.06251293 1.272555 0.3205384 1.272555 0.2944474 1.295579 0.2944474 1.158206 0.01933556 1.15839 0.07515925 1.152668 0.06678771 0.1602049 4.88286e-4 0.1602049 0.1149616 0.1656056 0.1149616 0.3668324 4.88286e-4 0.3795462 0.1296846 0.4252825 0.1296843 0.1602049 0.1149616 0.160205 0.1191003 0.1656055 0.1191003 0.718721 0.1367283 0.718721 0.2077418 0.8513208 0.18937 0.5584729 0.8715661 0.558473 0.8886547 0.6886763 0.8886547 0.122774 0.03978753 0.1267297 0.0226742 0.06735414 0.02267414 0.7187211 4.88286e-4 0.718721 0.1268674 0.8513209 0.1268674 0.9742742 0.475126 0.9995117 0.4751258 0.9995117 0.3395631 0.9742742 0.7152901 0.9995117 0.7152901 0.9995117 0.4839324 0.4301471 0.09963738 0.4301471 0.117868 0.4476855 0.1131566 0.7033466 0.1367283 0.718721 0.1367283 0.718721 0.1324492 0.9742742 0.4795293 0.9742742 0.4839326 0.9995117 0.4839324 0.1201953 0.6398431 0.1241632 0.6398431 0.1241632 0.6338987 0.9672788 0.8244635 0.9672788 0.8824383 0.9849687 0.8827466 0.9878022 0.1162673 0.9589474 0.1162674 0.9589475 0.1224743 0.4394726 0.4166052 0.46257 0.4166054 0.46257 0.2874245 0.9589475 0.1286842 0.9589475 0.3377504 0.9878022 0.3377475 0.1656056 0.123239 0.1602049 0.123239 0.160205 0.1693082 0.9589474 0.1162674 0.9878022 0.1162673 0.9878022 0.08591735 0.9507004 0.7686162 0.9507007 0.7764334 0.9672788 0.7764334 0.9589475 0.1224743 0.9589475 0.1286842 0.9878022 0.1286842 0.1656055 0.1191003 0.160205 0.1191003 0.1602049 0.123239 4.8841e-4 0.9054236 0.2079482 0.9054236 4.88282e-4 0.7880615 0.2079482 0.9054236 0.2121256 0.9040311 0.2135181 0.8998538 0.2135179 0.7880615 0.2079482 0.9054236 0.2135181 0.8998538 0.7033466 4.88286e-4 0.7033464 0.1268675 0.718721 0.1268674 0.851321 0.2727802 0.7187211 0.2598316 0.718721 0.3340762 0.04630947 0.2041161 0.04594987 0.2091332 0.09486085 0.2091332 0.5634874 0.9075481 0.6936855 0.9075482 0.6936855 0.8904688 0.1370818 0.1372556 0.1542612 0.1406455 0.1542612 0.08812946 0.5634765 0.8697519 0.6936799 0.8697519 0.6936799 0.8526635 0.9507005 0.554348 0.9507004 0.7686162 0.9672788 0.7686162 0.1102058 0.9344678 0.07420951 0.9344678 0.07455897 0.9395559 0.158074 0.19422 0.1752538 0.1976141 0.1752538 0.1711225 0.9698835 0.03194242 0.9878022 0.0278356 0.9878022 0.001010596 0.4497116 0.08430391 0.4321468 0.07959276 0.4321468 0.09782314 0.718721 0.1324492 0.718721 0.1268674 0.7033464 0.1268675 0.3667389 0.1830862 0.4183209 0.1830862 0.4183209 0.1695669 0.1241632 0.6338987 0.1241632 0.6398431 0.1281312 0.6398431 0.9672788 0.7764334 0.9507007 0.7764334 0.9507007 0.7841923 0.8513209 0.1312991 0.8513209 0.1268674 0.718721 0.1268674 5.41001e-4 0.9344677 8.27478e-4 0.939536 0.0719918 0.939536 0.9672788 0.8244635 0.9672788 0.7841923 0.9507007 0.7841923 0.9507007 0.7841923 0.9507004 0.9089362 0.9672788 0.8244635 0.9507004 0.9089362 0.9672788 0.9092137 0.9672788 0.8824383 0.558473 0.8697519 0.5634765 0.8697519 0.5634765 0.8526635 0.6886763 0.8715661 0.6886763 0.8886547 0.6936799 0.8886547 0.3343058 0.6398431 0.3343058 0.6338987 0.1281311 0.6338989 0.718721 0.1367283 0.8513209 0.1367283 0.8513209 0.1312991 0.9742742 0.475126 0.9742742 0.4795293 0.9995117 0.4795292 0.9698835 0.03194242 0.9589475 5.04342e-4 0.9589474 0.1162674 0.7033466 0.1367283 0.7033466 0.3603313 0.718721 0.2077418 0.5584729 0.9075482 0.5634874 0.9075481 0.5634874 0.8904688 4.88281e-4 0.6398431 0.1201953 0.6398431 0.1201952 0.6338989 1.160205 4.88286e-4 1.165606 4.88286e-4 1.165606 0.1149616 1.366832 4.88286e-4 1.437996 4.88286e-4 1.425282 0.1296843 1.165606 0.1191003 1.160205 0.1191003 1.160205 0.1149616 1.851321 0.18937 1.718721 0.2077418 1.718721 0.1367283 1.558473 0.8715661 1.688676 0.8715661 1.688676 0.8886547 1.122774 0.03978753 1.071192 0.03978765 1.067354 0.02267414 1.718721 4.88286e-4 1.851321 4.88286e-4 1.851321 0.1268674 1.999512 0.3395631 1.999512 0.4751258 1.974274 0.475126 1.999512 0.4839324 1.999512 0.7152901 1.974274 0.7152901 1.430147 0.09963738 1.447686 0.09963732 1.447685 0.1131566 1.703347 0.1367283 1.703346 0.1322978 1.718721 0.1324492 1.999512 0.4839324 1.974274 0.4839326 1.974274 0.4795293 1.124163 0.6338987 1.124163 0.6398431 1.120195 0.6398431 1.984969 0.8827466 1.967279 0.8824383 1.967279 0.8244635 1.987802 0.1162673 1.987802 0.1224736 1.958947 0.1224743 1.439473 0.4166052 1.426923 0.2874243 1.46257 0.2874245 1.958947 0.1286842 1.987802 0.1286842 1.987802 0.3377475 1.165606 0.123239 1.165606 0.1693081 1.160205 0.1693082 1.958947 0.1162674 1.969421 0.08381986 1.987802 0.08591735 1.967279 0.7764334 1.950701 0.7764334 1.9507 0.7686162 1.987802 0.1286842 1.958947 0.1286842 1.958947 0.1224743 1.165606 0.1191003 1.165606 0.123239 1.160205 0.123239 1.212126 0.9040311 1.207948 0.9054236 1.213518 0.8998538 1.207948 0.9054236 1.000488 0.9054236 1.000488 0.7880615 1.213518 0.7880615 1.207948 0.9054236 1.000488 0.7880615 1.718721 0.1268674 1.703346 0.1268675 1.703346 4.88286e-4 1.851321 0.2727802 1.851321 0.3212934 1.718721 0.3340762 1.046309 0.2041161 1.09455 0.2041161 1.094861 0.2091332 1.693686 0.8904688 1.693686 0.9075482 1.563487 0.9075481 1.137082 0.1372556 1.137082 0.09151941 1.154261 0.08812946 1.69368 0.8526635 1.69368 0.8697519 1.563477 0.8697519 1.9507 0.554348 1.967279 0.5542747 1.967279 0.7686162 1.110206 0.9344678 1.110206 0.9395559 1.074559 0.9395559 1.158074 0.19422 1.158074 0.1711224 1.175254 0.1711225 1.969883 0.03194242 1.958947 5.04342e-4 1.987802 0.001010596 1.432147 0.09782314 1.432147 0.07959276 1.449712 0.08430391 1.703346 0.1268675 1.718721 0.1268674 1.718721 0.1324492 1.418321 0.1695669 1.418321 0.1830862 1.366739 0.1830862 1.124163 0.6338987 1.128131 0.6338989 1.128131 0.6398431 1.967279 0.7764334 1.967279 0.7841923 1.950701 0.7841923 1.718721 0.1268674 1.851321 0.1268674 1.851321 0.1312991 1.000541 0.9344677 1.072278 0.934468 1.071992 0.939536 1.950701 0.7841923 1.967279 0.7841923 1.967279 0.8244635 1.967279 0.8824383 1.967279 0.9092137 1.9507 0.9089362 1.950701 0.7841923 1.967279 0.8244635 1.9507 0.9089362 1.563477 0.8526635 1.563477 0.8697519 1.558473 0.8697519 1.688676 0.8715661 1.69368 0.8715661 1.69368 0.8886547 1.334306 0.6398431 1.128131 0.6398431 1.128131 0.6338989 1.718721 0.1367283 1.718721 0.1324492 1.851321 0.1312991 1.999512 0.4795292 1.974274 0.4795293 1.974274 0.475126 1.969883 0.03194242 1.969421 0.08381986 1.958947 0.1162674 1.718721 0.2077418 1.703346 0.3603313 1.703347 0.1367283 1.563487 0.8904688 1.563487 0.9075481 1.558473 0.9075482 1.000488 0.6398431 1.000488 0.6338987 1.120195 0.6338989 1.160205 4.88286e-4 1.165606 4.88286e-4 1.165606 0.1149616 1.366832 4.88286e-4 1.437996 4.88286e-4 1.425282 0.1296843 1.165606 0.1191003 1.160205 0.1191003 1.160205 0.1149616 1.851321 0.18937 1.718721 0.2077418 1.718721 0.1367283 1.558473 0.8715661 1.688676 0.8715661 1.688676 0.8886547 1.122774 0.03978753 1.071192 0.03978765 1.067354 0.02267414 1.718721 4.88286e-4 1.851321 4.88286e-4 1.851321 0.1268674 1.999512 0.3395631 1.999512 0.4751258 1.974274 0.475126 1.999512 0.4839324 1.999512 0.7152901 1.974274 0.7152901 1.430147 0.09963738 1.447686 0.09963732 1.447685 0.1131566 1.703347 0.1367283 1.703346 0.1322978 1.718721 0.1324492 1.999512 0.4839324 1.974274 0.4839326 1.974274 0.4795293 1.124163 0.6338987 1.124163 0.6398431 1.120195 0.6398431 1.984969 0.8827466 1.967279 0.8824383 1.967279 0.8244635 1.987802 0.1162673 1.987802 0.1224736 1.958947 0.1224743 1.439473 0.4166052 1.426923 0.2874243 1.46257 0.2874245 1.958947 0.1286842 1.987802 0.1286842 1.987802 0.3377475 1.165606 0.123239 1.165606 0.1693081 1.160205 0.1693082 1.958947 0.1162674 1.969421 0.08381986 1.987802 0.08591735 1.967279 0.7764334 1.950701 0.7764334 1.9507 0.7686162 1.987802 0.1286842 1.958947 0.1286842 1.958947 0.1224743 1.165606 0.1191003 1.165606 0.123239 1.160205 0.123239 1.212126 0.9040311 1.207948 0.9054236 1.213518 0.8998538 1.207948 0.9054236 1.000488 0.9054236 1.000488 0.7880615 1.213518 0.7880615 1.207948 0.9054236 1.000488 0.7880615 1.718721 0.1268674 1.703346 0.1268675 1.703346 4.88286e-4 1.851321 0.2727802 1.851321 0.3212934 1.718721 0.3340762 1.046309 0.2041161 1.09455 0.2041161 1.094861 0.2091332 1.693686 0.8904688 1.693686 0.9075482 1.563487 0.9075481 1.137082 0.1372556 1.137082 0.09151941 1.154261 0.08812946 1.69368 0.8526635 1.69368 0.8697519 1.563477 0.8697519 1.9507 0.554348 1.967279 0.5542747 1.967279 0.7686162 1.110206 0.9344678 1.110206 0.9395559 1.074559 0.9395559 1.158074 0.19422 1.158074 0.1711224 1.175254 0.1711225 1.969883 0.03194242 1.958947 5.04342e-4 1.987802 0.001010596 1.432147 0.09782314 1.432147 0.07959276 1.449712 0.08430391 1.703346 0.1268675 1.718721 0.1268674 1.718721 0.1324492 1.418321 0.1695669 1.418321 0.1830862 1.366739 0.1830862 1.124163 0.6338987 1.128131 0.6338989 1.128131 0.6398431 1.967279 0.7764334 1.967279 0.7841923 1.950701 0.7841923 1.718721 0.1268674 1.851321 0.1268674 1.851321 0.1312991 1.000541 0.9344677 1.072278 0.934468 1.071992 0.939536 1.950701 0.7841923 1.967279 0.7841923 1.967279 0.8244635 1.967279 0.8824383 1.967279 0.9092137 1.9507 0.9089362 1.950701 0.7841923 1.967279 0.8244635 1.9507 0.9089362 1.563477 0.8526635 1.563477 0.8697519 1.558473 0.8697519 1.688676 0.8715661 1.69368 0.8715661 1.69368 0.8886547 1.334306 0.6398431 1.128131 0.6398431 1.128131 0.6338989 1.718721 0.1367283 1.718721 0.1324492 1.851321 0.1312991 1.999512 0.4795292 1.974274 0.4795293 1.974274 0.475126 1.969883 0.03194242 1.969421 0.08381986 1.958947 0.1162674 1.718721 0.2077418 1.703346 0.3603313 1.703347 0.1367283 1.563487 0.8904688 1.563487 0.9075481 1.558473 0.9075482 1.000488 0.6398431 1.000488 0.6338987 1.120195 0.6338989 1.160205 4.88286e-4 1.160205 0.1149616 1.165606 0.1149616 1.366832 4.88286e-4 1.379546 0.1296846 1.425282 0.1296843 1.160205 0.1149616 1.160205 0.1191003 1.165606 0.1191003 1.718721 0.1367283 1.718721 0.2077418 1.851321 0.18937 1.558473 0.8715661 1.558473 0.8886547 1.688676 0.8886547 1.122774 0.03978753 1.12673 0.0226742 1.067354 0.02267414 1.718721 4.88286e-4 1.718721 0.1268674 1.851321 0.1268674 1.974274 0.475126 1.999512 0.4751258 1.999512 0.3395631 1.974274 0.7152901 1.999512 0.7152901 1.999512 0.4839324 1.430147 0.09963738 1.430147 0.117868 1.447685 0.1131566 1.703347 0.1367283 1.718721 0.1367283 1.718721 0.1324492 1.974274 0.4795293 1.974274 0.4839326 1.999512 0.4839324 1.120195 0.6398431 1.124163 0.6398431 1.124163 0.6338987 1.967279 0.8244635 1.967279 0.8824383 1.984969 0.8827466 1.987802 0.1162673 1.958947 0.1162674 1.958947 0.1224743 1.439473 0.4166052 1.46257 0.4166054 1.46257 0.2874245 1.958947 0.1286842 1.958947 0.3377504 1.987802 0.3377475 1.165606 0.123239 1.160205 0.123239 1.160205 0.1693082 1.958947 0.1162674 1.987802 0.1162673 1.987802 0.08591735 1.9507 0.7686162 1.950701 0.7764334 1.967279 0.7764334 1.958947 0.1224743 1.958947 0.1286842 1.987802 0.1286842 1.165606 0.1191003 1.160205 0.1191003 1.160205 0.123239 1.000488 0.9054236 1.207948 0.9054236 1.000488 0.7880615 1.207948 0.9054236 1.212126 0.9040311 1.213518 0.8998538 1.213518 0.7880615 1.207948 0.9054236 1.213518 0.8998538 1.703346 4.88286e-4 1.703346 0.1268675 1.718721 0.1268674 1.851321 0.2727802 1.718721 0.2598316 1.718721 0.3340762 1.046309 0.2041161 1.04595 0.2091332 1.094861 0.2091332 1.563487 0.9075481 1.693686 0.9075482 1.693686 0.8904688 1.137082 0.1372556 1.154261 0.1406455 1.154261 0.08812946 1.563477 0.8697519 1.69368 0.8697519 1.69368 0.8526635 1.9507 0.554348 1.9507 0.7686162 1.967279 0.7686162 1.110206 0.9344678 1.07421 0.9344678 1.074559 0.9395559 1.158074 0.19422 1.175254 0.1976141 1.175254 0.1711225 1.969883 0.03194242 1.987802 0.0278356 1.987802 0.001010596 1.449712 0.08430391 1.432147 0.07959276 1.432147 0.09782314 1.718721 0.1324492 1.718721 0.1268674 1.703346 0.1268675 1.366739 0.1830862 1.418321 0.1830862 1.418321 0.1695669 1.124163 0.6338987 1.124163 0.6398431 1.128131 0.6398431 1.967279 0.7764334 1.950701 0.7764334 1.950701 0.7841923 1.851321 0.1312991 1.851321 0.1268674 1.718721 0.1268674 1.000541 0.9344677 1.000827 0.939536 1.071992 0.939536 1.967279 0.8244635 1.967279 0.7841923 1.950701 0.7841923 1.950701 0.7841923 1.9507 0.9089362 1.967279 0.8244635 1.9507 0.9089362 1.967279 0.9092137 1.967279 0.8824383 1.558473 0.8697519 1.563477 0.8697519 1.563477 0.8526635 1.688676 0.8715661 1.688676 0.8886547 1.69368 0.8886547 1.334306 0.6398431 1.334306 0.6338987 1.128131 0.6338989 1.718721 0.1367283 1.851321 0.1367283 1.851321 0.1312991 1.974274 0.475126 1.974274 0.4795293 1.999512 0.4795292 1.969883 0.03194242 1.958947 5.04342e-4 1.958947 0.1162674 1.703347 0.1367283 1.703346 0.3603313 1.718721 0.2077418 1.558473 0.9075482 1.563487 0.9075481 1.563487 0.8904688 1.000488 0.6398431 1.120195 0.6398431 1.120195 0.6338989 + + +0.509955 0.238046 +0.500928 0.238046 +0.594754 0.238046 +0.621930 0.238046 +0.647400 0.238046 +0.634670 0.238046 +0.277685 0.238046 +0.289041 0.238046 +0.288927 0.352781 +0.277664 0.352753 +0.288558 0.507599 +0.288453 0.551719 +0.277192 0.551693 +0.277297 0.507572 +0.288562 0.049774 +0.277200 0.049777 +0.277192 0.013475 +0.288554 0.013473 +0.288606 0.163569 +0.277245 0.163573 +0.621677 0.353612 +0.634494 0.353644 +0.647178 0.353675 +0.634105 0.508429 +0.646789 0.508460 +0.042014 0.399207 +0.042173 0.622093 +0.023392 0.622107 +0.495139 0.357654 +0.495139 0.502252 +0.290098 0.502251 +0.015133 0.614196 +0.006348 0.399232 +0.005976 0.389640 +0.042007 0.389615 +0.005847 0.380047 +0.042001 0.380022 +0.005756 0.247125 +0.041911 0.247100 +0.005871 0.237532 +0.041904 0.237507 +0.006229 0.227939 +0.041898 0.227914 +0.341429 0.669267 +0.341521 0.630671 +0.351113 0.630864 +0.351021 0.669289 +0.360704 0.631396 +0.360613 0.669311 +0.646680 0.552582 +0.633996 0.552551 +0.621811 0.049686 +0.621799 0.013390 +0.634625 0.013386 +0.634637 0.049681 +0.231068 0.669005 +0.008144 0.668470 +0.008186 0.650941 +0.016125 0.642581 +0.231159 0.631083 +0.240753 0.630598 +0.240662 0.669028 +0.250347 0.630452 +0.250255 0.669050 +0.290098 0.357654 +0.292263 0.053667 +0.497084 0.053667 +0.480916 0.560508 +0.490508 0.560507 +0.490508 0.586476 +0.480916 0.586476 +0.471323 0.586476 +0.471323 0.560508 +0.338400 0.586476 +0.338400 0.560507 +0.328807 0.586476 +0.328807 0.560507 +0.319215 0.586476 +0.319215 0.560507 +0.647318 0.013382 +0.647331 0.049676 +0.621854 0.163467 +0.634683 0.163463 +0.647379 0.163459 +0.500306 0.552222 +0.500411 0.508101 +0.509808 0.160514 +0.512800 0.151544 +0.550900 0.152083 +0.550903 0.161100 +0.352952 0.595709 +0.352952 0.622199 +0.343359 0.622199 +0.343359 0.595709 +0.444126 0.622199 +0.444126 0.595710 +0.453719 0.595710 +0.453719 0.622199 +0.463312 0.622199 +0.463312 0.595710 +0.333767 0.622199 +0.333767 0.595709 +0.014711 0.012941 +0.022959 0.005017 +0.041742 0.005004 +0.575631 0.643924 +0.583527 0.652320 +0.583485 0.669845 +0.534442 0.560507 +0.534442 0.570203 +0.530321 0.582407 +0.497084 0.159746 +0.292263 0.159746 +0.600907 0.503904 +0.585307 0.505322 +0.585191 0.552430 +0.550298 0.552345 +0.550414 0.504976 +0.594800 0.163476 +0.621180 0.552519 +0.621289 0.508397 +0.512399 0.496181 +0.512724 0.365289 +0.550761 0.365434 +0.550436 0.496053 +0.582669 0.365463 +0.517958 0.586475 +0.291766 0.586475 +0.279402 0.582407 +0.275281 0.570204 +0.275281 0.560507 +0.490761 0.595710 +0.503125 0.599778 +0.507246 0.611982 +0.507246 0.622200 +0.289833 0.611981 +0.293954 0.599777 +0.306317 0.595709 +0.289833 0.622199 +0.600907 0.358516 +0.644841 0.358516 +0.644841 0.503904 +0.645767 0.158929 +0.601833 0.158929 +0.601833 0.055316 +0.645767 0.055316 +0.591806 0.501099 +0.591806 0.361322 +0.588772 0.492682 +0.588772 0.369739 +0.503511 0.360445 +0.582342 0.496354 +0.509757 0.356320 +0.500795 0.353310 +0.594647 0.353544 +0.585678 0.356509 +0.550783 0.356495 +0.509387 0.505135 +0.594261 0.508331 +0.594152 0.552452 +0.509273 0.552244 +0.585908 0.264616 +0.586026 0.238046 +0.585829 0.160489 +0.551013 0.264529 +0.506302 0.368816 +0.506302 0.491090 +0.503511 0.499461 +0.505447 0.056454 +0.505447 0.156959 +0.508234 0.064816 +0.508234 0.148597 +0.592732 0.156207 +0.592732 0.058039 +0.589698 0.148039 +0.589698 0.066207 +0.053836 0.006887 +0.271977 0.006887 +0.271977 0.051695 +0.551019 0.238046 +0.582836 0.151520 +0.512770 0.061681 +0.550870 0.062221 +0.582806 0.061658 +0.500826 0.163506 +0.509772 0.052712 +0.509761 0.013422 +0.550855 0.013411 +0.262281 0.051695 +0.262281 0.208885 +0.271977 0.208885 +0.271977 0.296529 +0.253221 0.315285 +0.206108 0.315285 +0.206108 0.305067 +0.268496 0.311803 +0.090666 0.305067 +0.090666 0.315285 +0.053835 0.315285 +0.053835 0.296385 +0.550867 0.053299 +0.594748 0.013398 +0.594760 0.049695 +0.585792 0.052688 +0.500787 0.049725 +0.500778 0.013424 +0.585779 0.013400 +0.621899 0.264706 +0.594869 0.264639 +0.509980 0.266718 +0.501011 0.267196 +0.647394 0.267370 +0.634714 0.265388 +0.289112 0.278497 +0.277846 0.280173 +0.500840 0.210537 +0.509824 0.210895 +0.594815 0.212515 +0.621870 0.212507 +0.634698 0.211852 +0.647394 0.209896 +0.277256 0.200514 +0.288618 0.202094 +0.585846 0.212518 +0.550919 0.212529 +0.063298 0.608889 +0.064356 0.624018 +0.072849 0.608221 +0.073906 0.623351 +0.059018 0.616834 +0.073380 0.615856 +0.088605 0.623383 +0.098176 0.623627 +0.088992 0.608221 +0.083977 0.615636 +0.098563 0.608466 +0.641416 0.636173 +0.594242 0.636173 +0.652737 0.636173 +0.520040 0.636173 +0.549914 0.636173 +0.533717 0.636173 +0.631208 0.636173 +0.578964 0.593583 +0.595183 0.582872 +0.548334 0.593975 +0.550405 0.599486 +0.600664 0.636173 +0.622756 0.636173 +0.620898 0.606294 +0.597315 0.614358 +0.537764 0.607027 +0.543266 0.608018 +0.546259 0.602368 +0.541724 0.598521 +0.606017 0.584028 +0.584923 0.595727 +0.590792 0.601939 +0.618560 0.590582 +0.538975 0.636173 +0.574129 0.600303 +0.552727 0.604521 +0.556745 0.611089 +0.572737 0.608178 +0.601573 0.574935 +0.598578 0.564875 +0.541748 0.581076 +0.546075 0.589034 +0.640359 0.602493 +0.652072 0.602236 +0.591238 0.616834 +0.583894 0.619802 +0.586507 0.636173 +0.532811 0.605736 +0.537916 0.595295 +0.531299 0.589493 +0.524464 0.602860 +0.550483 0.606202 +0.548038 0.609557 +0.554009 0.612938 +0.555398 0.611435 +0.640150 0.566562 +0.651953 0.566002 +0.621179 0.564708 +0.629249 0.567065 +0.098370 0.616003 +0.614952 0.557887 +0.616065 0.572913 +0.610143 0.561345 +0.579180 0.601789 +0.575824 0.609191 +0.543437 0.636173 +0.528602 0.636173 +0.584914 0.606245 +0.579411 0.611984 +0.629373 0.604187 +1.578964 0.593583 +1.550405 0.599486 +1.548334 0.593975 +1.595183 0.582872 +1.600664 0.636173 +1.597315 0.614358 +1.620898 0.606294 +1.622756 0.636173 +1.537764 0.607027 +1.541724 0.598521 +1.546259 0.602368 +1.543266 0.608018 +1.606017 0.584028 +1.618560 0.590582 +1.590792 0.601939 +1.584923 0.595727 +1.533717 0.636173 +1.538975 0.636173 +1.574129 0.600303 +1.572737 0.608178 +1.556745 0.611089 +1.552727 0.604521 +1.601573 0.574935 +1.546075 0.589034 +1.541748 0.581076 +1.598578 0.564875 +1.640359 0.602493 +1.652072 0.602236 +1.652737 0.636173 +1.641416 0.636173 +1.594242 0.636173 +1.586507 0.636173 +1.583894 0.619802 +1.591238 0.616834 +1.532811 0.605736 +1.524464 0.602860 +1.531299 0.589493 +1.537916 0.595295 +1.550483 0.606202 +1.555398 0.611435 +1.554009 0.612938 +1.548038 0.609557 +1.640151 0.566562 +1.651953 0.566002 +1.088992 0.608221 +1.098562 0.608466 +1.098370 0.616003 +1.083977 0.615636 +1.616065 0.572913 +1.610143 0.561345 +1.614952 0.557887 +1.621179 0.564708 +1.579180 0.601789 +1.575824 0.609191 +1.549914 0.636173 +1.543437 0.636173 +1.528602 0.636173 +1.520040 0.636173 +1.579411 0.611984 +1.584913 0.606245 +1.629373 0.604187 +1.631208 0.636173 +1.098176 0.623627 +1.088605 0.623383 +1.629249 0.567065 +1.500840 0.210537 +1.509824 0.210895 +1.509955 0.238046 +1.500928 0.238046 +1.621899 0.264706 +1.594869 0.264639 +1.594754 0.238046 +1.621930 0.238046 +1.509980 0.266718 +1.501011 0.267196 +1.594815 0.212515 +1.621870 0.212507 +1.634698 0.211852 +1.647393 0.209896 +1.647400 0.238046 +1.634670 0.238046 +1.647393 0.267370 +1.634714 0.265388 +1.289112 0.278497 +1.277846 0.280173 +1.277685 0.238046 +1.289042 0.238046 +1.277256 0.200514 +1.288618 0.202094 +1.288927 0.352781 +1.277664 0.352753 +1.288558 0.507599 +1.288453 0.551719 +1.277192 0.551693 +1.277297 0.507572 +1.042014 0.399207 +1.042173 0.622093 +1.023392 0.622107 +1.015133 0.614196 +1.006348 0.399232 +1.005976 0.389640 +1.042007 0.389615 +1.005847 0.380047 +1.042001 0.380022 +1.005756 0.247125 +1.041911 0.247100 +1.005871 0.237532 +1.041904 0.237507 +1.006229 0.227939 +1.041898 0.227914 +1.288562 0.049774 +1.277200 0.049777 +1.277192 0.013475 +1.288554 0.013473 +1.288606 0.163569 +1.277245 0.163573 +1.341429 0.669267 +1.341521 0.630671 +1.351113 0.630864 +1.351021 0.669289 +1.360704 0.631396 +1.360613 0.669311 +1.231068 0.669005 +1.008144 0.668470 +1.008186 0.650941 +1.016124 0.642581 +1.231159 0.631083 +1.240754 0.630598 +1.240662 0.669028 +1.250347 0.630452 +1.250255 0.669050 +1.621677 0.353612 +1.634494 0.353644 +1.647178 0.353675 +1.634105 0.508429 +1.646789 0.508460 +1.646680 0.552582 +1.633996 0.552551 +1.480916 0.560508 +1.490508 0.560507 +1.490508 0.586476 +1.480916 0.586476 +1.471323 0.586476 +1.471323 0.560508 +1.338400 0.586476 +1.338400 0.560507 +1.328807 0.586476 +1.328807 0.560507 +1.319215 0.586476 +1.319215 0.560507 +1.621811 0.049686 +1.621799 0.013390 +1.634625 0.013386 +1.634637 0.049681 +1.647318 0.013382 +1.647331 0.049676 +1.621854 0.163467 +1.634683 0.163463 +1.647379 0.163459 +1.352952 0.595709 +1.352952 0.622199 +1.343359 0.622199 +1.343359 0.595709 +1.444126 0.622199 +1.444126 0.595710 +1.453719 0.595710 +1.453719 0.622199 +1.463312 0.622199 +1.463312 0.595710 +1.333767 0.622199 +1.333767 0.595709 +1.500306 0.552222 +1.500411 0.508101 +1.014711 0.012941 +1.022959 0.005017 +1.041742 0.005004 +1.495139 0.357654 +1.495139 0.502252 +1.290098 0.502251 +1.290098 0.357654 +1.509808 0.160514 +1.512800 0.151544 +1.550900 0.152083 +1.550903 0.161100 +1.575631 0.643924 +1.583527 0.652320 +1.583485 0.669845 +1.292263 0.053667 +1.497084 0.053667 +1.497084 0.159746 +1.292263 0.159746 +1.585307 0.505322 +1.585191 0.552430 +1.550298 0.552345 +1.550414 0.504976 +1.534441 0.560507 +1.534442 0.570203 +1.530321 0.582407 +1.517958 0.586475 +1.291766 0.586475 +1.279402 0.582407 +1.275281 0.570204 +1.275281 0.560507 +1.600907 0.503904 +1.600907 0.358516 +1.644841 0.358516 +1.644841 0.503904 +1.053836 0.006887 +1.271977 0.006887 +1.271977 0.051695 +1.262281 0.051695 +1.594800 0.163476 +1.490761 0.595710 +1.503125 0.599778 +1.507246 0.611982 +1.507246 0.622200 +1.645767 0.158929 +1.601833 0.158929 +1.601833 0.055316 +1.645767 0.055316 +1.289833 0.611981 +1.293954 0.599777 +1.306317 0.595709 +1.289833 0.622199 +1.621180 0.552519 +1.621289 0.508397 +1.262281 0.208885 +1.271977 0.208885 +1.271977 0.296529 +1.253222 0.315285 +1.206108 0.315285 +1.206108 0.305067 +1.268496 0.311803 +1.090666 0.305067 +1.090666 0.315285 +1.053835 0.315285 +1.053835 0.296385 +1.512399 0.496181 +1.512724 0.365289 +1.550761 0.365434 +1.550436 0.496053 +1.582669 0.365463 +1.582342 0.496354 +1.509757 0.356320 +1.500795 0.353310 +1.594647 0.353544 +1.585678 0.356509 +1.550783 0.356495 +1.509387 0.505135 +1.594260 0.508331 +1.594152 0.552452 +1.509273 0.552244 +1.585908 0.264616 +1.586026 0.238046 +1.585846 0.212518 +1.585829 0.160489 +1.551013 0.264529 +1.551019 0.238046 +1.550920 0.212529 +1.582836 0.151520 +1.512770 0.061681 +1.550870 0.062221 +1.582806 0.061658 +1.500826 0.163506 +1.509772 0.052712 +1.509761 0.013422 +1.550855 0.013411 +1.550867 0.053299 +1.594748 0.013398 +1.594760 0.049695 +1.585792 0.052688 +1.500787 0.049725 +1.500778 0.013424 +1.585779 0.013400 +1.591806 0.501099 +1.591806 0.361322 +1.588772 0.492682 +1.588772 0.369739 +1.503511 0.360445 +1.506302 0.368816 +1.506302 0.491090 +1.503511 0.499461 +1.505447 0.056454 +1.505447 0.156959 +1.508234 0.064816 +1.508234 0.148597 +1.592732 0.156207 +1.592732 0.058039 +1.589698 0.148039 +1.589698 0.066207 +1.064356 0.624018 +1.059018 0.616834 +1.073380 0.615856 +1.073906 0.623351 +1.063298 0.608889 +1.072849 0.608221 +1.578964 0.593583 +1.550405 0.599486 +1.548334 0.593975 +1.595183 0.582872 +1.600664 0.636173 +1.597315 0.614358 +1.620898 0.606294 +1.622756 0.636173 +1.537764 0.607027 +1.541724 0.598521 +1.546259 0.602368 +1.543266 0.608018 +1.606017 0.584028 +1.618560 0.590582 +1.590792 0.601939 +1.584923 0.595727 +1.533717 0.636173 +1.538975 0.636173 +1.574129 0.600303 +1.572737 0.608178 +1.556745 0.611089 +1.552727 0.604521 +1.601573 0.574935 +1.546075 0.589034 +1.541748 0.581076 +1.598578 0.564875 +1.640359 0.602493 +1.652072 0.602236 +1.652737 0.636173 +1.641416 0.636173 +1.594242 0.636173 +1.586507 0.636173 +1.583894 0.619802 +1.591238 0.616834 +1.532811 0.605736 +1.524464 0.602860 +1.531299 0.589493 +1.537916 0.595295 +1.550483 0.606202 +1.555398 0.611435 +1.554009 0.612938 +1.548038 0.609557 +1.640151 0.566562 +1.651953 0.566002 +1.088992 0.608221 +1.098562 0.608466 +1.098370 0.616003 +1.083977 0.615636 +1.616065 0.572913 +1.610143 0.561345 +1.614952 0.557887 +1.621179 0.564708 +1.579180 0.601789 +1.575824 0.609191 +1.549914 0.636173 +1.543437 0.636173 +1.528602 0.636173 +1.520040 0.636173 +1.579411 0.611984 +1.584913 0.606245 +1.629373 0.604187 +1.631208 0.636173 +1.098176 0.623627 +1.088605 0.623383 +1.629249 0.567065 +2.578964 0.593583 +2.595183 0.582872 +2.548334 0.593975 +2.550405 0.599486 +2.600664 0.636173 +2.622756 0.636173 +2.620898 0.606294 +2.597315 0.614358 +2.537764 0.607027 +2.543266 0.608018 +2.546259 0.602368 +2.541724 0.598521 +2.606017 0.584028 +2.584923 0.595727 +2.590792 0.601939 +2.618560 0.590582 +2.533717 0.636173 +2.538975 0.636173 +2.574129 0.600303 +2.552727 0.604521 +2.556745 0.611089 +2.572737 0.608178 +2.601573 0.574935 +2.598578 0.564875 +2.541748 0.581076 +2.546075 0.589034 +2.640359 0.602493 +2.641416 0.636173 +2.652737 0.636173 +2.652072 0.602236 +2.594242 0.636173 +2.591238 0.616834 +2.583894 0.619802 +2.586507 0.636173 +2.532811 0.605736 +2.537916 0.595295 +2.531299 0.589493 +2.524464 0.602860 +2.550483 0.606202 +2.548038 0.609557 +2.554009 0.612938 +2.555398 0.611435 +2.640151 0.566562 +2.651953 0.566002 +2.088992 0.608221 +2.083977 0.615636 +2.098370 0.616003 +2.098562 0.608466 +2.616065 0.572913 +2.621179 0.564708 +2.614953 0.557887 +2.610143 0.561345 +2.579180 0.601789 +2.575824 0.609191 +2.543437 0.636173 +2.549914 0.636173 +2.528602 0.636173 +2.520040 0.636173 +2.584913 0.606245 +2.579411 0.611984 +2.631208 0.636173 +2.629373 0.604187 +2.088605 0.623383 +2.098176 0.623627 +2.629249 0.567065 +1.500840 0.210537 +1.509824 0.210895 +1.509955 0.238046 +1.500928 0.238046 +1.621899 0.264706 +1.594869 0.264639 +1.594754 0.238046 +1.621930 0.238046 +1.509980 0.266718 +1.501011 0.267196 +1.594815 0.212515 +1.621870 0.212507 +1.634698 0.211852 +1.647393 0.209896 +1.647400 0.238046 +1.634670 0.238046 +1.647393 0.267370 +1.634714 0.265388 +1.289112 0.278497 +1.277846 0.280173 +1.277685 0.238046 +1.289042 0.238046 +1.277256 0.200514 +1.288618 0.202094 +1.288927 0.352781 +1.277664 0.352753 +1.288558 0.507599 +1.288453 0.551719 +1.277192 0.551693 +1.277297 0.507572 +1.042014 0.399207 +1.042173 0.622093 +1.023392 0.622107 +1.015133 0.614196 +1.006348 0.399232 +1.005976 0.389640 +1.042007 0.389615 +1.005847 0.380047 +1.042001 0.380022 +1.005756 0.247125 +1.041911 0.247100 +1.005871 0.237532 +1.041904 0.237507 +1.006229 0.227939 +1.041898 0.227914 +1.288562 0.049774 +1.277200 0.049777 +1.277192 0.013475 +1.288554 0.013473 +1.288606 0.163569 +1.277245 0.163573 +1.341429 0.669267 +1.341521 0.630671 +1.351113 0.630864 +1.351021 0.669289 +1.360704 0.631396 +1.360613 0.669311 +1.231068 0.669005 +1.008144 0.668470 +1.008186 0.650941 +1.016124 0.642581 +1.231159 0.631083 +1.240754 0.630598 +1.240662 0.669028 +1.250347 0.630452 +1.250255 0.669050 +1.621677 0.353612 +1.634494 0.353644 +1.647178 0.353675 +1.634105 0.508429 +1.646789 0.508460 +1.646680 0.552582 +1.633996 0.552551 +1.480916 0.560508 +1.490508 0.560507 +1.490508 0.586476 +1.480916 0.586476 +1.471323 0.586476 +1.471323 0.560508 +1.338400 0.586476 +1.338400 0.560507 +1.328807 0.586476 +1.328807 0.560507 +1.319215 0.586476 +1.319215 0.560507 +1.621811 0.049686 +1.621799 0.013390 +1.634625 0.013386 +1.634637 0.049681 +1.647318 0.013382 +1.647331 0.049676 +1.621854 0.163467 +1.634683 0.163463 +1.647379 0.163459 +1.352952 0.595709 +1.352952 0.622199 +1.343359 0.622199 +1.343359 0.595709 +1.444126 0.622199 +1.444126 0.595710 +1.453719 0.595710 +1.453719 0.622199 +1.463312 0.622199 +1.463312 0.595710 +1.333767 0.622199 +1.333767 0.595709 +1.500306 0.552222 +1.500411 0.508101 +1.014711 0.012941 +1.022959 0.005017 +1.041742 0.005004 +1.495139 0.357654 +1.495139 0.502252 +1.290098 0.502251 +1.290098 0.357654 +1.509808 0.160514 +1.512800 0.151544 +1.550900 0.152083 +1.550903 0.161100 +1.575631 0.643924 +1.583527 0.652320 +1.583485 0.669845 +1.292263 0.053667 +1.497084 0.053667 +1.497084 0.159746 +1.292263 0.159746 +1.585307 0.505322 +1.585191 0.552430 +1.550298 0.552345 +1.550414 0.504976 +1.534441 0.560507 +1.534442 0.570203 +1.530321 0.582407 +1.517958 0.586475 +1.291766 0.586475 +1.279402 0.582407 +1.275281 0.570204 +1.275281 0.560507 +1.600907 0.503904 +1.600907 0.358516 +1.644841 0.358516 +1.644841 0.503904 +1.053836 0.006887 +1.271977 0.006887 +1.271977 0.051695 +1.262281 0.051695 +1.594800 0.163476 +1.490761 0.595710 +1.503125 0.599778 +1.507246 0.611982 +1.507246 0.622200 +1.645767 0.158929 +1.601833 0.158929 +1.601833 0.055316 +1.645767 0.055316 +1.289833 0.611981 +1.293954 0.599777 +1.306317 0.595709 +1.289833 0.622199 +1.621180 0.552519 +1.621289 0.508397 +1.262281 0.208885 +1.271977 0.208885 +1.271977 0.296529 +1.253222 0.315285 +1.206108 0.315285 +1.206108 0.305067 +1.268496 0.311803 +1.090666 0.305067 +1.090666 0.315285 +1.053835 0.315285 +1.053835 0.296385 +1.512399 0.496181 +1.512724 0.365289 +1.550761 0.365434 +1.550436 0.496053 +1.582669 0.365463 +1.582342 0.496354 +1.509757 0.356320 +1.500795 0.353310 +1.594647 0.353544 +1.585678 0.356509 +1.550783 0.356495 +1.509387 0.505135 +1.594260 0.508331 +1.594152 0.552452 +1.509273 0.552244 +1.585908 0.264616 +1.586026 0.238046 +1.585846 0.212518 +1.585829 0.160489 +1.551013 0.264529 +1.551019 0.238046 +1.550920 0.212529 +1.582836 0.151520 +1.512770 0.061681 +1.550870 0.062221 +1.582806 0.061658 +1.500826 0.163506 +1.509772 0.052712 +1.509761 0.013422 +1.550855 0.013411 +1.550867 0.053299 +1.594748 0.013398 +1.594760 0.049695 +1.585792 0.052688 +1.500787 0.049725 +1.500778 0.013424 +1.585779 0.013400 +1.591806 0.501099 +1.591806 0.361322 +1.588772 0.492682 +1.588772 0.369739 +1.503511 0.360445 +1.506302 0.368816 +1.506302 0.491090 +1.503511 0.499461 +1.505447 0.056454 +1.505447 0.156959 +1.508234 0.064816 +1.508234 0.148597 +1.592732 0.156207 +1.592732 0.058039 +1.589698 0.148039 +1.589698 0.066207 +1.064356 0.624018 +1.059018 0.616834 +1.073380 0.615856 +1.073906 0.623351 +1.063298 0.608889 +1.072849 0.608221 +1.578964 0.593583 +1.550405 0.599486 +1.548334 0.593975 +1.595183 0.582872 +1.600664 0.636173 +1.597315 0.614358 +1.620898 0.606294 +1.622756 0.636173 +1.537764 0.607027 +1.541724 0.598521 +1.546259 0.602368 +1.543266 0.608018 +1.606017 0.584028 +1.618560 0.590582 +1.590792 0.601939 +1.584923 0.595727 +1.533717 0.636173 +1.538975 0.636173 +1.574129 0.600303 +1.572737 0.608178 +1.556745 0.611089 +1.552727 0.604521 +1.601573 0.574935 +1.546075 0.589034 +1.541748 0.581076 +1.598578 0.564875 +1.640359 0.602493 +1.652072 0.602236 +1.652737 0.636173 +1.641416 0.636173 +1.594242 0.636173 +1.586507 0.636173 +1.583894 0.619802 +1.591238 0.616834 +1.532811 0.605736 +1.524464 0.602860 +1.531299 0.589493 +1.537916 0.595295 +1.550483 0.606202 +1.555398 0.611435 +1.554009 0.612938 +1.548038 0.609557 +1.640151 0.566562 +1.651953 0.566002 +1.088992 0.608221 +1.098562 0.608466 +1.098370 0.616003 +1.083977 0.615636 +1.616065 0.572913 +1.610143 0.561345 +1.614952 0.557887 +1.621179 0.564708 +1.579180 0.601789 +1.575824 0.609191 +1.549914 0.636173 +1.543437 0.636173 +1.528602 0.636173 +1.520040 0.636173 +1.579411 0.611984 +1.584913 0.606245 +1.629373 0.604187 +1.631208 0.636173 +1.098176 0.623627 +1.088605 0.623383 +1.629249 0.567065 +2.578964 0.593583 +2.595183 0.582872 +2.548334 0.593975 +2.550405 0.599486 +2.600664 0.636173 +2.622756 0.636173 +2.620898 0.606294 +2.597315 0.614358 +2.537764 0.607027 +2.543266 0.608018 +2.546259 0.602368 +2.541724 0.598521 +2.606017 0.584028 +2.584923 0.595727 +2.590792 0.601939 +2.618560 0.590582 +2.533717 0.636173 +2.538975 0.636173 +2.574129 0.600303 +2.552727 0.604521 +2.556745 0.611089 +2.572737 0.608178 +2.601573 0.574935 +2.598578 0.564875 +2.541748 0.581076 +2.546075 0.589034 +2.640359 0.602493 +2.641416 0.636173 +2.652737 0.636173 +2.652072 0.602236 +2.594242 0.636173 +2.591238 0.616834 +2.583894 0.619802 +2.586507 0.636173 +2.532811 0.605736 +2.537916 0.595295 +2.531299 0.589493 +2.524464 0.602860 +2.550483 0.606202 +2.548038 0.609557 +2.554009 0.612938 +2.555398 0.611435 +2.640151 0.566562 +2.651953 0.566002 +2.088992 0.608221 +2.083977 0.615636 +2.098370 0.616003 +2.098562 0.608466 +2.616065 0.572913 +2.621179 0.564708 +2.614953 0.557887 +2.610143 0.561345 +2.579180 0.601789 +2.575824 0.609191 +2.543437 0.636173 +2.549914 0.636173 +2.528602 0.636173 +2.520040 0.636173 +2.584913 0.606245 +2.579411 0.611984 +2.631208 0.636173 +2.629373 0.604187 +2.088605 0.623383 +2.098176 0.623627 +2.629249 0.567065 +1.500840 0.210537 +1.500928 0.238046 +1.509955 0.238046 +1.509824 0.210895 +1.621899 0.264706 +1.621930 0.238046 +1.594754 0.238046 +1.594869 0.264639 +1.501011 0.267196 +1.509980 0.266718 +1.621870 0.212507 +1.594815 0.212515 +1.634698 0.211852 +1.634670 0.238046 +1.647400 0.238046 +1.647393 0.209896 +1.634714 0.265388 +1.647393 0.267370 +1.289112 0.278497 +1.289042 0.238046 +1.277685 0.238046 +1.277846 0.280173 +1.288618 0.202094 +1.277256 0.200514 +1.277664 0.352753 +1.288927 0.352781 +1.288558 0.507599 +1.277297 0.507572 +1.277192 0.551693 +1.288453 0.551719 +1.042014 0.399207 +1.006348 0.399232 +1.015133 0.614196 +1.023392 0.622107 +1.042173 0.622093 +1.042007 0.389615 +1.005976 0.389640 +1.042001 0.380022 +1.005847 0.380047 +1.041911 0.247100 +1.005756 0.247125 +1.041904 0.237507 +1.005871 0.237532 +1.041898 0.227914 +1.006229 0.227939 +1.288562 0.049774 +1.288554 0.013473 +1.277192 0.013475 +1.277200 0.049777 +1.288606 0.163569 +1.277245 0.163573 +1.341429 0.669267 +1.351021 0.669289 +1.351113 0.630864 +1.341521 0.630671 +1.360613 0.669311 +1.360704 0.631396 +1.231068 0.669005 +1.231159 0.631083 +1.016124 0.642581 +1.008186 0.650941 +1.008144 0.668470 +1.240662 0.669028 +1.240754 0.630598 +1.250255 0.669050 +1.250347 0.630452 +1.621677 0.353612 +1.634494 0.353644 +1.647178 0.353675 +1.634105 0.508429 +1.633996 0.552551 +1.646680 0.552582 +1.646789 0.508460 +1.480916 0.560508 +1.480916 0.586476 +1.490508 0.586476 +1.490508 0.560507 +1.471323 0.586476 +1.471323 0.560508 +1.338400 0.586476 +1.338400 0.560507 +1.328807 0.586476 +1.328807 0.560507 +1.319215 0.586476 +1.319215 0.560507 +1.621811 0.049686 +1.634637 0.049681 +1.634625 0.013386 +1.621799 0.013390 +1.647331 0.049676 +1.647318 0.013382 +1.621854 0.163467 +1.634683 0.163463 +1.647379 0.163459 +1.352952 0.595709 +1.343359 0.595709 +1.343359 0.622199 +1.352952 0.622199 +1.444126 0.622199 +1.444126 0.595710 +1.453719 0.595710 +1.453719 0.622199 +1.463312 0.622199 +1.463312 0.595710 +1.333767 0.595709 +1.333767 0.622199 +1.500306 0.552222 +1.500411 0.508101 +1.014711 0.012941 +1.041742 0.005004 +1.022959 0.005017 +1.495139 0.357654 +1.290098 0.357654 +1.290098 0.502251 +1.495139 0.502252 +1.509808 0.160514 +1.550903 0.161100 +1.550900 0.152083 +1.512800 0.151544 +1.575631 0.643924 +1.583485 0.669845 +1.583527 0.652320 +1.292263 0.053667 +1.292263 0.159746 +1.497084 0.159746 +1.497084 0.053667 +1.585307 0.505322 +1.550414 0.504976 +1.550298 0.552345 +1.585191 0.552430 +1.517958 0.586475 +1.530321 0.582407 +1.534442 0.570203 +1.534441 0.560507 +1.291766 0.586475 +1.275281 0.560507 +1.275281 0.570204 +1.279402 0.582407 +1.600907 0.503904 +1.644841 0.503904 +1.644841 0.358516 +1.600907 0.358516 +1.053836 0.006887 +1.262281 0.051695 +1.271977 0.051695 +1.271977 0.006887 +1.594800 0.163476 +1.507246 0.622200 +1.507246 0.611982 +1.503125 0.599778 +1.490761 0.595710 +1.645767 0.158929 +1.645767 0.055316 +1.601833 0.055316 +1.601833 0.158929 +1.289833 0.611981 +1.289833 0.622199 +1.306317 0.595709 +1.293954 0.599777 +1.621180 0.552519 +1.621289 0.508397 +1.262281 0.208885 +1.206108 0.305067 +1.206108 0.315285 +1.253222 0.315285 +1.271977 0.296529 +1.271977 0.208885 +1.268496 0.311803 +1.090666 0.305067 +1.053835 0.296385 +1.053835 0.315285 +1.090666 0.315285 +1.512399 0.496181 +1.550436 0.496053 +1.550761 0.365434 +1.512724 0.365289 +1.582342 0.496354 +1.582669 0.365463 +1.509757 0.356320 +1.500795 0.353310 +1.594647 0.353544 +1.585678 0.356509 +1.550783 0.356495 +1.509387 0.505135 +1.594152 0.552452 +1.594260 0.508331 +1.509273 0.552244 +1.585908 0.264616 +1.586026 0.238046 +1.585846 0.212518 +1.585829 0.160489 +1.551013 0.264529 +1.551019 0.238046 +1.550920 0.212529 +1.582836 0.151520 +1.550870 0.062221 +1.512770 0.061681 +1.582806 0.061658 +1.500826 0.163506 +1.509772 0.052712 +1.550867 0.053299 +1.550855 0.013411 +1.509761 0.013422 +1.594748 0.013398 +1.594760 0.049695 +1.585792 0.052688 +1.500778 0.013424 +1.500787 0.049725 +1.585779 0.013400 +1.591806 0.361322 +1.591806 0.501099 +1.588772 0.369739 +1.588772 0.492682 +1.503511 0.360445 +1.503511 0.499461 +1.506302 0.491090 +1.506302 0.368816 +1.505447 0.156959 +1.505447 0.056454 +1.508234 0.148597 +1.508234 0.064816 +1.592732 0.058039 +1.592732 0.156207 +1.589698 0.066207 +1.589698 0.148039 +1.064356 0.624018 +1.073906 0.623351 +1.073380 0.615856 +1.059018 0.616834 +1.072849 0.608221 +1.063298 0.608889 +1.578964 0.593583 +1.595183 0.582872 +1.548334 0.593975 +1.550405 0.599486 +1.600664 0.636173 +1.622756 0.636173 +1.620898 0.606294 +1.597315 0.614358 +1.537764 0.607027 +1.543266 0.608018 +1.546259 0.602368 +1.541724 0.598521 +1.606017 0.584028 +1.584923 0.595727 +1.590792 0.601939 +1.618560 0.590582 +1.533717 0.636173 +1.538975 0.636173 +1.574129 0.600303 +1.552727 0.604521 +1.556745 0.611089 +1.572737 0.608178 +1.601573 0.574935 +1.598578 0.564875 +1.541748 0.581076 +1.546075 0.589034 +1.640359 0.602493 +1.641416 0.636173 +1.652737 0.636173 +1.652072 0.602236 +1.594242 0.636173 +1.591238 0.616834 +1.583894 0.619802 +1.586507 0.636173 +1.532811 0.605736 +1.537916 0.595295 +1.531299 0.589493 +1.524464 0.602860 +1.550483 0.606202 +1.548038 0.609557 +1.554009 0.612938 +1.555398 0.611435 +1.640151 0.566562 +1.651953 0.566002 +1.088992 0.608221 +1.083977 0.615636 +1.098370 0.616003 +1.098562 0.608466 +1.616065 0.572913 +1.621179 0.564708 +1.614952 0.557887 +1.610143 0.561345 +1.579180 0.601789 +1.575824 0.609191 +1.543437 0.636173 +1.549914 0.636173 +1.528602 0.636173 +1.520040 0.636173 +1.584913 0.606245 +1.579411 0.611984 +1.631208 0.636173 +1.629373 0.604187 +1.088605 0.623383 +1.098176 0.623627 +1.629249 0.567065 +2.578964 0.593583 +2.550405 0.599486 +2.548334 0.593975 +2.595183 0.582872 +2.600664 0.636173 +2.597315 0.614358 +2.620898 0.606294 +2.622756 0.636173 +2.537764 0.607027 +2.541724 0.598521 +2.546259 0.602368 +2.543266 0.608018 +2.606017 0.584028 +2.618560 0.590582 +2.590792 0.601939 +2.584923 0.595727 +2.533717 0.636173 +2.538975 0.636173 +2.574129 0.600303 +2.572737 0.608178 +2.556745 0.611089 +2.552727 0.604521 +2.601573 0.574935 +2.546075 0.589034 +2.541748 0.581076 +2.598578 0.564875 +2.640359 0.602493 +2.652072 0.602236 +2.652737 0.636173 +2.641416 0.636173 +2.594242 0.636173 +2.586507 0.636173 +2.583894 0.619802 +2.591238 0.616834 +2.532811 0.605736 +2.524464 0.602860 +2.531299 0.589493 +2.537916 0.595295 +2.550483 0.606202 +2.555398 0.611435 +2.554009 0.612938 +2.548038 0.609557 +2.640151 0.566562 +2.651953 0.566002 +2.088992 0.608221 +2.098562 0.608466 +2.098370 0.616003 +2.083977 0.615636 +2.616065 0.572913 +2.610143 0.561345 +2.614953 0.557887 +2.621179 0.564708 +2.579180 0.601789 +2.575824 0.609191 +2.549914 0.636173 +2.543437 0.636173 +2.528602 0.636173 +2.520040 0.636173 +2.579411 0.611984 +2.584913 0.606245 +2.629373 0.604187 +2.631208 0.636173 +2.098176 0.623627 +2.088605 0.623383 +2.629249 0.567065 +1.262281 0.006887 +1.262281 0.006887 +1.262281 0.006887 +0.262281 0.006887 +0.992633 0.473342 +0.236014 0.831592 +0.231256 0.452642 +0.972927 0.577680 +0.975829 0.583166 +0.442577 0.962489 +0.992633 0.210666 +0.480513 0.930627 +0.675717 0.962489 +0.236108 0.336894 +0.851290 0.583002 +0.231156 0.399649 +0.851394 0.577885 +0.239799 0.388204 +0.239799 0.517400 +0.239799 0.468551 +0.271984 0.831376 +0.272768 0.961728 +0.249461 0.961868 +0.248498 0.403037 +0.248585 0.449188 +0.215761 0.554936 +0.215329 0.326646 +0.077359 0.968226 +0.236108 0.388568 +0.253080 0.464409 +0.005205 0.968587 +0.231019 0.327494 +0.231399 0.528174 +0.012026 0.834817 +0.253080 0.392346 +0.256849 0.392056 +0.998765 0.210666 +0.981719 0.716999 +0.675717 0.992558 +0.998765 0.473342 +0.713971 0.930628 +0.442577 0.992558 +0.982423 0.732677 +0.851060 0.732582 +0.256849 0.464699 +0.236108 0.517714 +0.236108 0.468186 +0.992633 0.587900 +0.231450 0.554906 +0.381748 0.845024 +0.992633 0.483372 +0.713971 0.956094 +0.382211 0.901385 +0.063518 0.834559 +0.248742 0.531566 +0.256849 0.521140 +0.248786 0.554873 +0.480513 0.956094 +0.253066 0.521494 +0.364851 0.899360 +0.364851 0.846571 +0.407447 0.962489 +0.433148 0.962489 +0.334831 0.930628 +0.407447 0.980479 +0.471627 0.930627 +0.336926 0.992546 +0.471627 0.956094 +0.366812 0.980479 +0.433274 0.992546 +0.253066 0.557591 +0.256849 0.557591 +0.140297 0.962465 +0.094146 0.962710 +0.080625 0.832410 +0.152435 0.832029 +0.232672 0.967380 +0.157141 0.967803 +0.169564 0.833997 +0.218918 0.833721 +0.851063 0.716876 +0.998765 0.483372 +0.998765 0.587900 +0.334831 0.956095 +0.336926 0.962489 +0.239799 0.340611 +0.366812 0.962489 +0.991340 0.732126 +0.986902 0.732539 +0.986155 0.716839 +0.990581 0.716383 +0.978225 0.577554 +0.979836 0.583294 +0.983729 0.581993 +0.992633 0.478259 +0.437920 0.962489 +0.998765 0.478259 +0.476070 0.930627 +0.437920 0.992558 +0.982439 0.575272 +0.760296 0.738714 +0.764511 0.737309 +0.973855 0.737337 +0.973839 0.855766 +0.758875 0.855737 +0.476070 0.956094 +0.758890 0.742929 +0.298739 0.845949 +0.298739 0.879636 +0.298739 0.938598 +0.298739 0.964787 +0.282117 0.964787 +0.282117 0.830169 +0.026675 0.980329 +0.246888 0.980329 +0.263510 0.996108 +0.026675 0.996108 +0.317401 0.879636 +0.317401 0.938598 +0.251164 0.978946 +0.267786 0.994726 +0.346194 0.917335 +0.351016 0.899360 +0.364851 0.917335 +0.351016 0.846571 +0.346194 0.828623 +0.364851 0.828623 +0.252590 0.974798 +0.269211 0.990577 +1.760296 0.738714 +1.764511 0.737309 +1.973855 0.737337 +1.973839 0.855766 +1.758875 0.855737 +1.758890 0.742929 +1.236014 0.831592 +1.271984 0.831376 +1.272768 0.961728 +1.249461 0.961868 +1.480513 0.930627 +1.713971 0.930628 +1.713971 0.956094 +1.480513 0.956094 +1.992633 0.473342 +1.992633 0.210666 +1.998765 0.210666 +1.998765 0.473342 +1.298739 0.845949 +1.298739 0.879636 +1.298739 0.938598 +1.298739 0.964787 +1.282117 0.964787 +1.282117 0.830169 +1.442577 0.962489 +1.675717 0.962489 +1.675717 0.992558 +1.442577 0.992558 +1.972927 0.577680 +1.975829 0.583166 +1.851290 0.583002 +1.851394 0.577885 +1.981719 0.716999 +1.982423 0.732677 +1.851060 0.732582 +1.851063 0.716876 +1.077359 0.968226 +1.005205 0.968587 +1.012026 0.834817 +1.063518 0.834559 +1.140297 0.962465 +1.094146 0.962710 +1.080625 0.832410 +1.152435 0.832029 +1.232672 0.967380 +1.157141 0.967803 +1.169564 0.833997 +1.218917 0.833721 +1.236108 0.388568 +1.236108 0.336894 +1.239799 0.340611 +1.239799 0.388204 +1.253080 0.464409 +1.253080 0.392346 +1.256849 0.392056 +1.256849 0.464699 +1.236108 0.517714 +1.236108 0.468186 +1.239799 0.468551 +1.239799 0.517400 +1.256849 0.521140 +1.253066 0.521494 +1.231256 0.452642 +1.231156 0.399649 +1.248498 0.403037 +1.248585 0.449188 +1.334831 0.930628 +1.471627 0.930627 +1.471627 0.956094 +1.334831 0.956095 +1.992633 0.587900 +1.992633 0.483372 +1.998765 0.483372 +1.998765 0.587900 +1.381748 0.845024 +1.382211 0.901385 +1.364851 0.899360 +1.364851 0.846571 +1.026675 0.980329 +1.246888 0.980329 +1.263510 0.996108 +1.026675 0.996108 +1.253066 0.557591 +1.256849 0.557591 +1.215761 0.554936 +1.215329 0.326646 +1.231019 0.327494 +1.231399 0.528174 +1.231450 0.554906 +1.248742 0.531566 +1.248786 0.554873 +1.407447 0.962489 +1.433148 0.962489 +1.433274 0.992546 +1.407447 0.980479 +1.336926 0.992546 +1.366812 0.980479 +1.336926 0.962489 +1.366812 0.962489 +1.317401 0.879636 +1.317401 0.938598 +1.346194 0.917335 +1.351016 0.899360 +1.364851 0.917335 +1.351016 0.846571 +1.346194 0.828623 +1.364851 0.828623 +1.991340 0.732126 +1.986902 0.732539 +1.986155 0.716839 +1.990581 0.716383 +1.476070 0.930627 +1.476070 0.956094 +1.992633 0.478259 +1.998765 0.478259 +1.251164 0.978946 +1.267786 0.994726 +1.437920 0.962489 +1.437920 0.992558 +1.978225 0.577554 +1.979836 0.583294 +1.983729 0.581993 +1.252590 0.974798 +1.269212 0.990577 +1.982439 0.575272 +1.760296 0.738714 +1.764511 0.737309 +1.973855 0.737337 +1.973839 0.855766 +1.758875 0.855737 +1.758890 0.742929 +1.236014 0.831592 +1.271984 0.831376 +1.272768 0.961728 +1.249461 0.961868 +1.480513 0.930627 +1.713971 0.930628 +1.713971 0.956094 +1.480513 0.956094 +1.992633 0.473342 +1.992633 0.210666 +1.998765 0.210666 +1.998765 0.473342 +1.298739 0.845949 +1.298739 0.879636 +1.298739 0.938598 +1.298739 0.964787 +1.282117 0.964787 +1.282117 0.830169 +1.442577 0.962489 +1.675717 0.962489 +1.675717 0.992558 +1.442577 0.992558 +1.972927 0.577680 +1.975829 0.583166 +1.851290 0.583002 +1.851394 0.577885 +1.981719 0.716999 +1.982423 0.732677 +1.851060 0.732582 +1.851063 0.716876 +1.077359 0.968226 +1.005205 0.968587 +1.012026 0.834817 +1.063518 0.834559 +1.140297 0.962465 +1.094146 0.962710 +1.080625 0.832410 +1.152435 0.832029 +1.232672 0.967380 +1.157141 0.967803 +1.169564 0.833997 +1.218917 0.833721 +1.236108 0.388568 +1.236108 0.336894 +1.239799 0.340611 +1.239799 0.388204 +1.253080 0.464409 +1.253080 0.392346 +1.256849 0.392056 +1.256849 0.464699 +1.236108 0.517714 +1.236108 0.468186 +1.239799 0.468551 +1.239799 0.517400 +1.256849 0.521140 +1.253066 0.521494 +1.231256 0.452642 +1.231156 0.399649 +1.248498 0.403037 +1.248585 0.449188 +1.334831 0.930628 +1.471627 0.930627 +1.471627 0.956094 +1.334831 0.956095 +1.992633 0.587900 +1.992633 0.483372 +1.998765 0.483372 +1.998765 0.587900 +1.381748 0.845024 +1.382211 0.901385 +1.364851 0.899360 +1.364851 0.846571 +1.026675 0.980329 +1.246888 0.980329 +1.263510 0.996108 +1.026675 0.996108 +1.253066 0.557591 +1.256849 0.557591 +1.215761 0.554936 +1.215329 0.326646 +1.231019 0.327494 +1.231399 0.528174 +1.231450 0.554906 +1.248742 0.531566 +1.248786 0.554873 +1.407447 0.962489 +1.433148 0.962489 +1.433274 0.992546 +1.407447 0.980479 +1.336926 0.992546 +1.366812 0.980479 +1.336926 0.962489 +1.366812 0.962489 +1.317401 0.879636 +1.317401 0.938598 +1.346194 0.917335 +1.351016 0.899360 +1.364851 0.917335 +1.351016 0.846571 +1.346194 0.828623 +1.364851 0.828623 +1.991340 0.732126 +1.986902 0.732539 +1.986155 0.716839 +1.990581 0.716383 +1.476070 0.930627 +1.476070 0.956094 +1.992633 0.478259 +1.998765 0.478259 +1.251164 0.978946 +1.267786 0.994726 +1.437920 0.962489 +1.437920 0.992558 +1.978225 0.577554 +1.979836 0.583294 +1.983729 0.581993 +1.252590 0.974798 +1.269212 0.990577 +1.982439 0.575272 +1.760296 0.738714 +1.758890 0.742929 +1.758875 0.855737 +1.973839 0.855766 +1.973855 0.737337 +1.764511 0.737309 +1.236014 0.831592 +1.249461 0.961868 +1.272768 0.961728 +1.271984 0.831376 +1.480513 0.930627 +1.480513 0.956094 +1.713971 0.956094 +1.713971 0.930628 +1.992633 0.473342 +1.998765 0.473342 +1.998765 0.210666 +1.992633 0.210666 +1.298739 0.845949 +1.282117 0.830169 +1.282117 0.964787 +1.298739 0.964787 +1.298739 0.938598 +1.298739 0.879636 +1.442577 0.962489 +1.442577 0.992558 +1.675717 0.992558 +1.675717 0.962489 +1.972927 0.577680 +1.851394 0.577885 +1.851290 0.583002 +1.975829 0.583166 +1.981719 0.716999 +1.851063 0.716876 +1.851060 0.732582 +1.982423 0.732677 +1.077359 0.968226 +1.063518 0.834559 +1.012026 0.834817 +1.005205 0.968587 +1.140297 0.962465 +1.152435 0.832029 +1.080625 0.832410 +1.094146 0.962710 +1.232672 0.967380 +1.218917 0.833721 +1.169564 0.833997 +1.157141 0.967803 +1.236108 0.388568 +1.239799 0.388204 +1.239799 0.340611 +1.236108 0.336894 +1.253080 0.464409 +1.256849 0.464699 +1.256849 0.392056 +1.253080 0.392346 +1.236108 0.517714 +1.239799 0.517400 +1.239799 0.468551 +1.236108 0.468186 +1.253066 0.521494 +1.256849 0.521140 +1.231256 0.452642 +1.248585 0.449188 +1.248498 0.403037 +1.231156 0.399649 +1.334831 0.930628 +1.334831 0.956095 +1.471627 0.956094 +1.471627 0.930627 +1.992633 0.587900 +1.998765 0.587900 +1.998765 0.483372 +1.992633 0.483372 +1.381748 0.845024 +1.364851 0.846571 +1.364851 0.899360 +1.382211 0.901385 +1.026675 0.980329 +1.026675 0.996108 +1.263510 0.996108 +1.246888 0.980329 +1.253066 0.557591 +1.256849 0.557591 +1.215761 0.554936 +1.231450 0.554906 +1.231399 0.528174 +1.231019 0.327494 +1.215329 0.326646 +1.248786 0.554873 +1.248742 0.531566 +1.407447 0.962489 +1.407447 0.980479 +1.433274 0.992546 +1.433148 0.962489 +1.366812 0.980479 +1.336926 0.992546 +1.366812 0.962489 +1.336926 0.962489 +1.317401 0.938598 +1.317401 0.879636 +1.346194 0.917335 +1.364851 0.917335 +1.351016 0.899360 +1.351016 0.846571 +1.364851 0.828623 +1.346194 0.828623 +1.991340 0.732126 +1.990581 0.716383 +1.986155 0.716839 +1.986902 0.732539 +1.476070 0.956094 +1.476070 0.930627 +1.998765 0.478259 +1.992633 0.478259 +1.267786 0.994726 +1.251164 0.978946 +1.437920 0.992558 +1.437920 0.962489 +1.979836 0.583294 +1.978225 0.577554 +1.983729 0.581993 +1.269212 0.990577 +1.252590 0.974798 +1.982439 0.575272 + - + - - + + - - - - -

33 0 0 18 1 1 20 2 2 33 0 3 20 2 4 21 3 5 33 0 6 21 3 7 22 4 8 34 5 9 22 4 10 28 6 11 75 7 12 93 8 13 92 9 14 51 10 15 36 11 16 38 12 17 51 10 18 38 12 19 39 13 20 51 10 21 39 13 22 40 14 23 112 15 24 44 16 25 45 17 26 39 18 27 117 19 28 118 20 29 9 21 30 66 22 31 96 23 32 65 24 33 71 25 34 70 26 35 243 27 36 63 27 37 54 27 38 23 28 39 19 29 40 30 30 41 24 31 42 23 28 43 30 30 44 24 31 45 30 30 46 25 32 47 41 33 48 37 33 49 50 34 50 42 33 51 41 33 52 50 34 53 42 33 54 50 34 55 43 35 56 64 36 57 94 37 58 95 38 59 63 39 60 62 40 61 60 41 62 54 42 63 63 39 64 60 41 65 56 43 66 57 44 67 58 45 68 56 43 69 58 45 70 55 46 71 240 47 72 62 48 73 122 49 74 101 50 75 13 51 76 102 52 77 77 53 78 78 54 79 76 55 80 79 56 81 77 53 82 76 55 83 83 57 84 80 58 85 81 59 86 83 57 87 81 59 88 82 60 89 3 61 90 83 27 91 74 62 92 5 63 93 3 61 94 74 62 95 5 63 96 4 64 97 3 61 98 55 27 99 74 62 100 239 65 101 9 21 102 107 66 103 13 51 104 74 62 105 75 67 106 239 65 107 239 65 108 54 27 109 55 27 110 75 67 111 115 27 112 239 65 113 70 68 114 71 69 115 72 70 116 72 70 117 69 71 118 70 68 119 35 72 120 32 73 121 31 74 122 31 74 123 34 75 124 35 72 125 53 76 126 48 77 127 49 78 128 49 78 129 52 79 130 53 76 131 88 80 132 90 81 133 91 82 134 91 82 135 89 83 136 88 80 137 137 84 138 140 85 139 139 86 140 138 87 141 127 88 142 128 89 143 160 90 144 158 91 145 157 92 146 229 93 147 207 94 148 208 95 149 201 96 150 211 97 151 212 98 152 175 99 153 151 100 154 206 101 155 201 102 156 182 103 157 200 104 158 129 105 159 127 88 160 130 106 161 229 107 162 194 108 163 225 109 164 137 84 165 128 89 166 145 110 167 145 110 168 167 111 169 137 84 170 187 112 171 227 113 172 195 114 173 140 85 174 167 111 175 173 115 176 173 115 177 124 116 178 178 117 179 173 115 180 131 118 181 140 85 182 140 85 183 137 84 184 167 111 185 163 119 186 164 120 187 173 115 188 173 115 189 167 111 190 163 119 191 196 121 192 180 122 193 199 123 194 132 124 195 186 125 196 183 126 197 193 127 198 192 128 199 191 129 200 182 103 201 179 130 202 194 108 203 216 131 204 214 132 205 213 133 206 177 134 207 153 135 208 227 136 209 176 137 210 215 138 211 216 131 212 204 139 213 218 27 214 217 140 215 200 141 216 202 142 217 201 96 218 155 143 219 148 144 220 154 145 221 181 146 222 179 130 223 182 103 224 141 147 225 130 106 226 127 88 227 191 129 228 223 148 229 200 104 230 200 104 231 182 103 232 191 129 233 192 128 234 230 149 235 223 148 236 222 150 237 204 139 238 217 140 239 230 149 240 192 128 241 185 151 242 192 128 243 223 148 244 191 129 245 219 152 246 223 148 247 230 149 248 230 149 249 222 150 250 219 152 251 110 153 252 106 154 253 107 66 254 15 155 255 4 156 256 17 157 257 1 158 258 8 159 259 0 160 260 47 161 261 48 162 262 44 163 263 10 164 264 82 165 265 81 166 266 53 167 267 44 163 268 48 162 269 86 168 270 92 169 271 91 170 272 62 48 273 116 171 274 122 49 275 93 172 276 83 57 277 82 60 278 232 27 279 75 67 280 76 27 281 94 37 282 27 173 283 95 38 284 82 60 285 89 174 286 93 172 287 123 175 288 61 176 289 241 177 290 105 178 291 85 179 292 87 180 293 85 179 294 112 15 295 84 181 296 113 182 297 84 181 298 112 15 299 45 17 300 113 182 301 112 15 302 25 183 303 242 184 304 237 185 305 79 186 306 234 187 307 121 40 308 93 8 309 91 82 310 92 9 311 199 188 312 197 189 313 196 190 314 225 191 315 228 192 316 229 93 317 213 133 318 198 193 319 199 188 320 188 194 321 201 102 322 212 195 323 221 11 324 217 11 325 218 11 326 185 151 327 193 127 328 184 196 329 162 27 330 149 197 331 161 198 332 172 199 333 169 200 334 171 201 335 147 202 336 145 203 337 148 144 338 152 204 339 171 201 340 151 100 341 209 205 342 177 134 343 227 136 344 12 206 345 109 207 346 8 208 347 14 209 348 100 210 349 10 164 350 4 156 351 16 211 352 17 157 353 10 164 354 17 157 355 14 209 356 17 157 357 11 212 358 14 209 359 73 213 360 56 43 361 55 46 362 6 214 363 1 158 364 2 215 365 21 216 366 0 160 367 8 159 368 76 217 369 119 218 370 232 219 371 25 32 372 31 220 373 29 221 374 29 221 375 32 222 376 26 223 377 52 224 378 40 14 379 46 225 380 53 167 381 46 225 382 45 226 383 5 227 384 57 228 385 16 211 386 67 229 387 68 230 388 61 231 389 24 232 390 236 233 391 23 234 392 71 25 393 66 235 394 72 236 395 43 35 396 49 237 397 47 161 398 87 238 399 88 239 400 89 174 401 90 240 402 86 168 403 91 170 404 61 176 405 240 47 406 241 177 407 237 185 408 24 241 409 25 183 410 105 178 411 44 16 412 104 242 413 37 243 414 51 244 415 50 245 416 238 246 417 67 247 418 123 175 419 69 248 420 65 24 421 70 26 422 35 249 423 26 223 424 32 222 425 5 63 426 55 27 427 58 27 428 77 250 429 119 218 430 78 251 431 97 252 432 26 253 433 94 37 434 27 173 435 96 23 436 95 38 437 99 254 438 103 255 439 100 210 440 102 52 441 7 256 442 103 255 443 82 165 444 103 255 445 87 180 446 103 255 447 105 178 448 87 180 449 108 257 450 22 258 451 109 207 452 107 66 453 7 256 454 13 51 455 96 23 456 108 257 457 9 21 458 111 259 459 12 206 460 6 260 461 43 261 462 6 260 463 42 262 464 46 263 465 233 264 466 113 182 467 120 265 468 40 266 469 114 267 470 114 267 471 39 268 472 118 269 473 233 264 474 86 270 475 113 182 476 33 271 477 19 272 478 18 273 479 238 246 480 29 274 481 97 252 482 30 275 483 34 75 484 31 74 485 51 244 486 49 78 487 50 245 488 135 276 489 133 277 490 136 278 491 128 89 492 139 86 493 138 87 494 134 279 495 195 114 496 133 277 497 129 105 498 135 276 499 136 278 500 139 86 501 131 118 502 132 124 503 144 280 504 142 281 505 141 282 506 150 27 507 124 116 508 149 197 509 124 116 510 205 27 511 204 139 512 143 283 513 157 92 514 142 281 515 156 284 516 154 145 517 153 135 518 131 118 519 178 117 520 186 125 521 183 126 522 151 285 523 132 124 524 157 286 525 134 279 526 135 276 527 209 287 528 188 194 529 212 195 530 171 288 531 138 87 532 139 86 533 158 289 534 174 290 535 134 279 536 227 113 537 133 277 538 195 114 539 130 106 540 157 286 541 135 276 542 184 196 543 229 107 544 208 291 545 164 120 546 149 197 547 173 115 548 184 196 549 186 125 550 185 151 551 169 292 552 127 88 553 138 87 554 190 293 555 195 114 556 174 290 557 159 294 558 176 137 559 158 91 560 165 33 561 163 33 562 166 33 563 167 111 564 166 295 565 163 119 566 145 203 567 168 296 568 167 297 569 185 151 570 178 117 571 230 149 572 183 126 573 208 291 574 206 298 575 180 122 576 213 299 577 199 123 578 153 300 579 136 278 580 133 277 581 225 109 582 179 130 583 196 121 584 216 301 585 174 290 586 176 302 587 230 149 588 124 116 589 204 139 590 80 303 591 3 304 592 15 155 593 35 249 594 28 6 595 27 305 596 98 306 597 102 52 598 99 254 599 2 215 600 42 307 601 6 214 602 98 306 603 56 308 604 59 309 605 15 155 606 81 166 607 80 303 608 85 310 609 90 240 610 88 239 611 60 41 612 68 230 613 54 42 614 54 311 615 73 312 616 55 313 617 76 55 618 92 169 619 79 56 620 96 23 621 64 36 622 95 38 623 65 314 624 97 252 625 94 37 626 59 309 627 101 50 628 98 306 629 72 236 630 59 315 631 73 213 632 43 261 633 106 154 634 111 259 635 106 154 636 105 178 637 7 256 638 108 257 639 110 153 640 107 66 641 8 208 642 22 258 643 21 316 644 16 211 645 56 308 646 11 212 647 121 40 648 77 250 649 79 186 650 68 317 651 72 70 652 73 312 653 189 318 654 187 112 655 190 293 656 182 103 657 193 127 658 191 129 659 181 146 660 189 318 661 180 122 662 170 319 663 141 282 664 169 200 665 196 190 666 226 320 667 225 191 668 200 141 669 224 321 670 203 322 671 136 278 672 148 323 673 129 105 674 165 33 675 161 33 676 164 33 677 208 95 678 175 324 679 206 325 680 212 98 681 210 326 682 209 205 683 219 11 684 221 11 685 220 11 686 223 148 687 220 327 688 224 328 689 213 299 690 190 293 691 216 301 692 171 288 693 132 124 694 151 285 695 11 212 696 99 254 697 14 209 698 54 27 699 239 65 700 243 27 701 148 323 702 128 89 703 129 105 704 277 329 705 264 330 706 262 331 707 277 329 708 265 332 709 264 330 710 277 329 711 266 4 712 265 332 713 278 333 714 266 4 715 277 329 716 337 334 717 319 335 718 336 336 719 295 337 720 282 338 721 280 33 722 295 337 723 283 339 724 282 338 725 295 337 726 284 340 727 283 339 728 356 341 729 288 342 730 348 343 731 117 344 732 283 345 733 118 346 734 253 347 735 310 348 736 345 349 737 315 350 738 309 351 739 314 352 740 307 27 741 475 27 742 298 27 743 267 353 744 274 354 745 263 355 746 268 356 747 274 354 748 267 353 749 268 356 750 269 357 751 274 354 752 285 11 753 294 358 754 281 11 755 286 11 756 294 358 757 285 11 758 286 11 759 287 359 760 294 358 761 308 360 762 338 361 763 309 362 764 307 40 765 304 363 766 306 40 767 298 40 768 304 363 769 307 40 770 300 364 771 302 365 772 301 366 773 300 364 774 299 367 775 302 365 776 306 368 777 472 369 778 359 370 779 257 371 780 345 349 781 346 372 782 321 373 783 320 374 784 322 375 785 323 376 786 320 374 787 321 373 788 327 377 789 325 378 790 324 379 791 327 377 792 326 380 793 325 378 794 247 381 795 318 382 796 327 27 797 249 381 798 318 382 799 247 381 800 249 381 801 247 381 802 248 383 803 299 27 804 239 384 805 318 382 806 253 347 807 351 385 808 352 386 809 318 382 810 239 384 811 319 387 812 239 384 813 299 27 814 298 27 815 319 387 816 239 384 817 115 27 818 314 388 819 316 389 820 315 390 821 316 389 822 314 388 823 313 391 824 279 392 825 275 393 826 276 394 827 275 393 828 279 392 829 278 395 830 297 396 831 293 397 832 292 398 833 293 397 834 297 396 835 296 399 836 332 400 837 335 401 838 334 402 839 335 401 840 332 400 841 333 403 842 374 404 843 376 405 844 377 406 845 375 407 846 365 408 847 364 409 848 395 410 849 397 411 850 394 412 851 444 413 852 466 414 853 445 100 854 448 143 855 438 144 856 449 415 857 388 416 858 412 417 859 443 325 860 438 418 861 419 419 862 418 420 863 366 421 864 364 409 865 365 408 866 466 422 867 431 423 868 430 424 869 374 404 870 382 425 871 365 408 872 382 425 873 374 404 874 404 426 875 464 427 876 424 428 877 432 429 878 377 406 879 410 430 880 404 426 881 410 430 882 361 431 883 386 432 884 410 430 885 377 406 886 368 433 887 377 406 888 404 426 889 374 404 890 400 434 891 410 430 892 401 435 893 410 430 894 400 434 895 404 426 896 433 436 897 417 437 898 416 438 899 369 439 900 423 440 901 368 433 902 430 424 903 428 441 904 429 442 905 419 419 906 431 423 907 416 438 908 451 443 909 453 444 910 450 445 911 390 446 912 414 447 913 464 328 914 452 294 915 413 27 916 453 444 917 455 27 918 441 432 919 454 448 920 439 202 921 437 449 922 438 144 923 385 450 924 392 451 925 391 452 926 418 420 927 416 438 928 417 437 929 378 453 930 367 454 931 379 455 932 428 441 933 437 456 934 460 457 935 437 456 936 428 441 937 419 419 938 429 442 939 460 457 940 467 458 941 459 435 942 441 432 943 467 458 944 467 458 945 422 459 946 429 442 947 429 442 948 428 441 949 460 457 950 456 460 951 467 458 952 460 457 953 467 458 954 456 460 955 459 435 956 354 461 957 350 462 958 355 463 959 259 464 960 248 465 961 247 466 962 245 467 963 252 468 964 256 469 965 291 470 966 292 471 967 293 472 968 326 473 969 254 474 970 325 166 971 288 475 972 297 476 973 292 471 974 330 477 975 336 478 976 323 376 977 358 479 978 306 368 979 359 370 980 337 480 981 327 377 982 318 11 983 232 27 984 319 387 985 115 27 986 338 361 987 271 481 988 270 482 989 333 483 990 326 380 991 337 480 992 360 484 993 305 485 994 311 486 995 329 487 996 349 488 997 331 489 998 329 487 999 356 341 1000 348 343 1001 357 490 1002 328 491 1003 330 492 1004 289 493 1005 357 490 1006 290 494 1007 474 495 1008 269 496 1009 470 497 1010 234 40 1011 323 40 1012 121 40 1013 336 336 1014 333 403 1015 337 334 1016 434 498 1017 436 499 1018 433 500 1019 465 501 1020 462 502 1021 466 414 1022 435 503 1023 450 445 1024 436 499 1025 425 504 1026 438 418 1027 418 420 1028 458 33 1029 454 33 1030 459 33 1031 430 424 1032 422 459 1033 421 505 1034 386 432 1035 399 27 1036 398 448 1037 406 506 1038 409 507 1039 408 508 1040 382 509 1041 384 510 1042 385 450 1043 408 508 1044 389 511 1045 388 416 1046 414 447 1047 446 512 1048 464 328 1049 256 513 1050 353 514 1051 354 461 1052 344 515 1053 258 516 1054 254 474 1055 260 517 1056 248 465 1057 261 518 1058 254 474 1059 261 518 1060 259 464 1061 255 519 1062 261 518 1063 258 516 1064 317 520 1065 300 364 1066 303 521 1067 250 522 1068 245 467 1069 256 469 1070 265 523 1071 244 524 1072 264 525 1073 320 526 1074 119 527 1075 322 528 1076 269 357 1077 275 529 1078 274 354 1079 273 530 1080 276 531 1081 275 529 1082 296 532 1083 284 340 1084 295 337 1085 297 476 1086 290 533 1087 296 532 1088 249 534 1089 301 535 1090 302 536 1091 312 537 1092 311 538 1093 305 539 1094 469 540 1095 268 541 1096 267 542 1097 315 350 1098 310 543 1099 308 544 1100 287 359 1101 293 472 1102 294 358 1103 332 545 1104 331 546 1105 333 483 1106 334 547 1107 330 477 1108 328 548 1109 472 369 1110 305 485 1111 473 549 1112 268 550 1113 470 497 1114 269 496 1115 349 488 1116 288 342 1117 291 551 1118 295 552 1119 281 553 1120 294 554 1121 471 555 1122 311 486 1123 341 556 1124 313 557 1125 309 351 1126 311 538 1127 270 558 1128 279 559 1129 276 531 1130 249 381 1131 299 27 1132 318 382 1133 119 527 1134 321 560 1135 322 528 1136 341 556 1137 270 482 1138 273 561 1139 271 481 1140 340 562 1141 272 563 1142 347 564 1143 343 565 1144 344 515 1145 251 566 1146 346 372 1147 347 564 1148 326 473 1149 347 564 1150 344 515 1151 349 488 1152 347 564 1153 331 489 1154 352 386 1155 266 567 1156 272 563 1157 351 385 1158 251 566 1159 350 462 1160 352 386 1161 340 562 1162 253 347 1163 355 463 1164 256 513 1165 354 461 1166 287 568 1167 250 569 1168 355 463 1169 233 570 1170 290 494 1171 357 490 1172 120 571 1173 284 572 1174 290 494 1175 283 573 1176 114 574 1177 118 575 1178 233 570 1179 330 492 1180 234 40 1181 263 576 1182 277 577 1183 262 578 1184 471 555 1185 273 561 1186 474 495 1187 274 579 1188 278 395 1189 277 577 1190 293 397 1191 295 552 1192 294 554 1193 372 580 1194 370 581 1195 371 582 1196 365 408 1197 376 405 1198 374 404 1199 371 582 1200 432 429 1201 411 583 1202 366 421 1203 372 580 1204 367 454 1205 368 433 1206 376 405 1207 369 439 1208 379 584 1209 381 585 1210 378 586 1211 361 431 1212 387 27 1213 386 432 1214 442 27 1215 361 431 1216 441 432 1217 394 412 1218 380 587 1219 379 584 1220 391 452 1221 393 588 1222 390 446 1223 368 433 1224 415 589 1225 410 430 1226 420 590 1227 388 591 1228 443 592 1229 394 593 1230 371 582 1231 395 594 1232 446 595 1233 425 504 1234 424 428 1235 408 596 1236 375 407 1237 406 597 1238 395 594 1239 411 583 1240 413 598 1241 370 581 1242 464 427 1243 432 429 1244 367 454 1245 394 593 1246 379 455 1247 466 422 1248 421 505 1249 445 599 1250 401 435 1251 386 432 1252 398 448 1253 421 505 1254 423 440 1255 420 590 1256 406 597 1257 364 409 1258 378 453 1259 427 600 1260 432 429 1261 424 428 1262 413 27 1263 396 601 1264 395 410 1265 400 11 1266 402 11 1267 403 11 1268 404 426 1269 403 602 1270 405 328 1271 382 509 1272 405 603 1273 383 322 1274 422 459 1275 415 589 1276 423 440 1277 420 590 1278 445 599 1279 421 505 1280 417 437 1281 450 604 1282 426 605 1283 390 606 1284 373 607 1285 391 608 1286 462 609 1287 416 438 1288 431 423 1289 453 610 1290 411 583 1291 427 600 1292 467 458 1293 361 431 1294 415 589 1295 324 303 1296 247 466 1297 327 611 1298 279 559 1299 272 612 1300 278 333 1301 346 372 1302 342 613 1303 343 565 1304 246 614 1305 286 615 1306 285 616 1307 300 617 1308 342 613 1309 303 618 1310 259 464 1311 325 166 1312 254 474 1313 329 619 1314 334 547 1315 328 548 1316 304 363 1317 312 537 1318 305 539 1319 317 620 1320 298 621 1321 299 622 1322 320 374 1323 336 478 1324 319 33 1325 340 562 1326 308 360 1327 310 348 1328 309 362 1329 341 556 1330 311 486 1331 345 349 1332 303 618 1333 342 613 1334 316 623 1335 303 521 1336 310 543 1337 287 568 1338 350 462 1339 291 551 1340 350 462 1341 349 488 1342 291 551 1343 352 386 1344 354 461 1345 353 514 1346 252 624 1347 266 567 1348 353 514 1349 260 517 1350 300 617 1351 301 535 1352 321 560 1353 121 40 1354 323 40 1355 316 389 1356 312 625 1357 317 620 1358 426 605 1359 424 428 1360 425 504 1361 430 424 1362 419 419 1363 428 441 1364 418 420 1365 426 605 1366 425 504 1367 378 586 1368 407 626 1369 406 506 1370 463 627 1371 433 500 1372 462 502 1373 437 449 1374 461 628 1375 460 297 1376 373 607 1377 385 629 1378 391 608 1379 402 11 1380 398 11 1381 399 11 1382 412 99 1383 445 100 1384 443 101 1385 447 630 1386 449 415 1387 446 512 1388 458 33 1389 456 33 1390 457 33 1391 460 457 1392 457 631 1393 456 460 1394 450 604 1395 427 600 1396 426 605 1397 369 439 1398 408 596 1399 388 591 1400 343 565 1401 255 519 1402 258 516 1403 298 27 1404 475 27 1405 239 384 1406 385 629 1407 365 408 1408 382 425 1409 509 632 1410 496 633 1411 494 40 1412 509 632 1413 497 634 1414 496 633 1415 509 632 1416 498 635 1417 497 634 1418 510 636 1419 498 635 1420 509 632 1421 569 637 1422 551 638 1423 568 639 1424 527 640 1425 514 641 1426 512 11 1427 527 640 1428 515 642 1429 514 641 1430 527 640 1431 516 14 1432 515 642 1433 588 643 1434 520 644 1435 580 645 1436 592 646 1437 515 647 1438 593 648 1439 485 649 1440 542 22 1441 577 650 1442 547 651 1443 541 652 1444 546 653 1445 539 27 1446 243 27 1447 530 27 1448 499 654 1449 506 655 1450 495 656 1451 500 657 1452 506 655 1453 499 654 1454 500 657 1455 501 658 1456 506 655 1457 517 659 1458 526 660 1459 513 33 1460 518 661 1461 526 660 1462 517 659 1463 518 661 1464 519 35 1465 526 660 1466 540 662 1467 570 663 1468 541 314 1469 539 664 1470 536 665 1471 538 331 1472 530 666 1473 536 665 1474 539 664 1475 532 667 1476 534 668 1477 533 669 1478 532 667 1479 531 670 1480 534 668 1481 538 48 1482 240 671 1483 122 49 1484 489 672 1485 577 650 1486 578 673 1487 553 674 1488 552 675 1489 554 676 1490 555 677 1491 552 675 1492 553 674 1493 559 678 1494 557 679 1495 556 680 1496 559 678 1497 558 681 1498 557 679 1499 479 682 1500 550 683 1501 559 27 1502 481 684 1503 550 683 1504 479 682 1505 481 684 1506 479 682 1507 480 685 1508 531 27 1509 239 686 1510 550 683 1511 485 649 1512 583 687 1513 584 688 1514 550 683 1515 239 686 1516 551 689 1517 239 686 1518 531 27 1519 530 27 1520 551 689 1521 239 686 1522 591 27 1523 546 690 1524 548 691 1525 547 692 1526 548 691 1527 546 690 1528 545 693 1529 511 694 1530 507 695 1531 508 696 1532 507 695 1533 511 694 1534 510 697 1535 529 698 1536 525 699 1537 524 700 1538 525 699 1539 529 698 1540 528 701 1541 564 702 1542 567 703 1543 566 704 1544 567 703 1545 564 702 1546 565 705 1547 610 706 1548 612 707 1549 613 708 1550 611 709 1551 601 710 1552 600 711 1553 631 712 1554 633 90 1555 630 713 1556 680 94 1557 702 93 1558 681 95 1559 684 97 1560 674 96 1561 685 98 1562 624 100 1563 648 99 1564 679 101 1565 674 714 1566 655 715 1567 654 716 1568 602 717 1569 600 711 1570 601 710 1571 702 718 1572 667 719 1573 666 720 1574 610 706 1575 618 721 1576 601 710 1577 618 721 1578 610 706 1579 640 722 1580 700 723 1581 660 724 1582 668 725 1583 613 708 1584 646 726 1585 640 722 1586 646 726 1587 597 727 1588 622 728 1589 646 726 1590 613 708 1591 604 729 1592 613 708 1593 640 722 1594 610 706 1595 636 730 1596 646 726 1597 637 731 1598 646 726 1599 636 730 1600 640 722 1601 669 732 1602 653 733 1603 652 734 1604 605 735 1605 659 736 1606 604 729 1607 666 720 1608 664 737 1609 665 738 1610 655 715 1611 667 719 1612 652 734 1613 687 132 1614 689 131 1615 686 739 1616 626 135 1617 650 740 1618 700 136 1619 688 138 1620 649 741 1621 689 131 1622 691 27 1623 677 742 1624 690 743 1625 675 142 1626 673 141 1627 674 96 1628 621 744 1629 628 143 1630 627 145 1631 654 716 1632 652 734 1633 653 733 1634 614 745 1635 603 746 1636 615 747 1637 664 737 1638 673 748 1639 696 749 1640 673 748 1641 664 737 1642 655 715 1643 665 738 1644 696 749 1645 703 750 1646 695 751 1647 677 742 1648 703 750 1649 703 750 1650 658 752 1651 665 738 1652 665 738 1653 664 737 1654 696 749 1655 692 753 1656 703 750 1657 696 749 1658 703 750 1659 692 753 1660 695 751 1661 586 754 1662 582 755 1663 587 756 1664 491 757 1665 480 758 1666 479 759 1667 477 760 1668 484 761 1669 488 762 1670 523 763 1671 524 764 1672 525 237 1673 558 765 1674 486 766 1675 557 767 1676 520 768 1677 529 769 1678 524 764 1679 562 770 1680 568 771 1681 555 677 1682 116 171 1683 538 48 1684 122 49 1685 569 172 1686 559 678 1687 550 33 1688 705 27 1689 551 689 1690 591 27 1691 570 663 1692 503 772 1693 502 773 1694 565 174 1695 558 681 1696 569 172 1697 123 774 1698 537 176 1699 543 775 1700 561 776 1701 581 777 1702 563 778 1703 561 776 1704 588 643 1705 580 645 1706 589 779 1707 560 780 1708 562 781 1709 521 782 1710 589 779 1711 522 783 1712 242 784 1713 501 785 1714 237 786 1715 707 787 1716 555 788 1717 596 331 1718 567 703 1719 569 637 1720 568 639 1721 670 789 1722 672 790 1723 669 791 1724 701 192 1725 698 191 1726 702 93 1727 671 792 1728 686 739 1729 672 790 1730 661 793 1731 674 714 1732 654 716 1733 694 11 1734 690 11 1735 695 11 1736 666 720 1737 658 752 1738 657 794 1739 622 728 1740 635 27 1741 634 795 1742 642 200 1743 645 199 1744 644 201 1745 618 796 1746 620 797 1747 621 744 1748 644 201 1749 625 798 1750 624 100 1751 650 740 1752 682 799 1753 700 136 1754 488 800 1755 585 801 1756 586 754 1757 576 802 1758 490 803 1759 486 766 1760 492 804 1761 480 758 1762 493 805 1763 486 766 1764 493 805 1765 491 757 1766 487 806 1767 493 805 1768 490 803 1769 549 807 1770 532 667 1771 535 808 1772 482 809 1773 477 760 1774 488 762 1775 497 216 1776 476 810 1777 496 811 1778 552 812 1779 594 813 1780 554 814 1781 501 658 1782 507 815 1783 506 655 1784 505 816 1785 508 817 1786 507 815 1787 528 224 1788 516 14 1789 527 640 1790 529 769 1791 522 818 1792 528 224 1793 481 819 1794 533 820 1795 534 821 1796 544 822 1797 543 823 1798 537 824 1799 236 825 1800 500 826 1801 499 827 1802 547 651 1803 542 828 1804 540 829 1805 519 35 1806 525 237 1807 526 660 1808 564 239 1809 563 830 1810 565 174 1811 566 831 1812 562 770 1813 560 832 1814 240 671 1815 537 176 1816 241 177 1817 500 833 1818 237 786 1819 501 785 1820 581 777 1821 520 644 1822 523 834 1823 527 835 1824 513 836 1825 526 837 1826 238 838 1827 543 775 1828 573 839 1829 545 840 1830 541 652 1831 543 823 1832 502 841 1833 511 842 1834 508 817 1835 481 684 1836 531 27 1837 550 683 1838 594 813 1839 553 843 1840 554 814 1841 573 839 1842 502 773 1843 505 844 1844 503 772 1845 572 845 1846 504 846 1847 579 847 1848 575 848 1849 576 802 1850 483 849 1851 578 673 1852 579 847 1853 558 765 1854 579 847 1855 576 802 1856 581 777 1857 579 847 1858 563 778 1859 584 688 1860 498 258 1861 504 846 1862 583 687 1863 483 849 1864 582 755 1865 584 688 1866 572 845 1867 485 649 1868 587 756 1869 488 800 1870 586 754 1871 519 850 1872 482 851 1873 587 756 1874 706 852 1875 522 783 1876 589 779 1877 595 853 1878 516 854 1879 522 783 1880 515 855 1881 590 856 1882 593 857 1883 706 852 1884 562 781 1885 707 787 1886 495 858 1887 509 859 1888 494 860 1889 238 838 1890 505 844 1891 242 784 1892 506 861 1893 510 697 1894 509 859 1895 525 699 1896 527 835 1897 526 837 1898 608 862 1899 606 863 1900 607 864 1901 601 710 1902 612 707 1903 610 706 1904 607 864 1905 668 725 1906 647 865 1907 602 717 1908 608 862 1909 603 746 1910 604 729 1911 612 707 1912 605 735 1913 615 866 1914 617 867 1915 614 868 1916 597 727 1917 623 27 1918 622 728 1919 678 27 1920 597 727 1921 677 742 1922 630 713 1923 616 869 1924 615 866 1925 627 145 1926 629 870 1927 626 135 1928 604 729 1929 651 871 1930 646 726 1931 656 872 1932 624 873 1933 679 874 1934 630 875 1935 607 864 1936 631 876 1937 682 877 1938 661 793 1939 660 724 1940 644 878 1941 611 709 1942 642 879 1943 631 876 1944 647 865 1945 649 880 1946 606 863 1947 700 723 1948 668 725 1949 603 746 1950 630 875 1951 615 747 1952 702 718 1953 657 794 1954 681 881 1955 637 731 1956 622 728 1957 634 795 1958 657 794 1959 659 736 1960 656 872 1961 642 879 1962 600 711 1963 614 745 1964 663 882 1965 668 725 1966 660 724 1967 649 741 1968 632 883 1969 631 712 1970 636 33 1971 638 33 1972 639 33 1973 640 722 1974 639 295 1975 641 328 1976 618 796 1977 641 296 1978 619 884 1979 658 752 1980 651 871 1981 659 736 1982 656 872 1983 681 881 1984 657 794 1985 653 733 1986 686 885 1987 662 886 1988 626 887 1989 609 888 1990 627 889 1991 698 890 1992 652 734 1993 667 719 1994 689 891 1995 647 865 1996 663 882 1997 703 750 1998 597 727 1999 651 871 2000 556 892 2001 479 759 2002 559 893 2003 511 842 2004 504 894 2005 510 636 2006 578 673 2007 574 895 2008 575 848 2009 478 896 2010 518 897 2011 517 898 2012 532 899 2013 574 895 2014 535 309 2015 491 757 2016 557 767 2017 486 766 2018 561 310 2019 566 831 2020 560 832 2021 536 665 2022 544 822 2023 537 824 2024 549 900 2025 530 901 2026 531 901 2027 552 675 2028 568 771 2029 551 11 2030 572 845 2031 540 662 2032 542 22 2033 541 314 2034 573 839 2035 543 775 2036 577 650 2037 535 309 2038 574 895 2039 548 902 2040 535 808 2041 542 828 2042 519 850 2043 582 755 2044 523 834 2045 582 755 2046 581 777 2047 523 834 2048 584 688 2049 586 754 2050 585 801 2051 484 903 2052 498 258 2053 585 801 2054 492 804 2055 532 899 2056 533 820 2057 553 843 2058 596 331 2059 555 788 2060 548 691 2061 544 904 2062 549 900 2063 662 886 2064 660 724 2065 661 793 2066 666 720 2067 655 715 2068 664 737 2069 654 716 2070 662 886 2071 661 793 2072 614 868 2073 643 905 2074 642 200 2075 699 320 2076 669 791 2077 698 191 2078 673 141 2079 697 321 2080 696 906 2081 609 888 2082 621 907 2083 627 889 2084 638 33 2085 634 33 2086 635 33 2087 648 324 2088 681 95 2089 679 325 2090 683 326 2091 685 98 2092 682 799 2093 694 11 2094 692 11 2095 693 11 2096 696 749 2097 693 327 2098 692 753 2099 686 885 2100 663 882 2101 662 886 2102 605 735 2103 644 878 2104 624 873 2105 575 848 2106 487 806 2107 490 803 2108 530 27 2109 243 27 2110 239 686 2111 621 907 2112 601 710 2113 618 721 2114 741 632 2115 726 40 2116 728 908 2117 741 632 2118 728 908 2119 729 909 2120 741 632 2121 729 909 2122 730 910 2123 742 911 2124 730 910 2125 736 912 2126 783 913 2127 801 914 2128 800 915 2129 759 916 2130 744 33 2131 746 917 2132 759 916 2133 746 917 2134 747 918 2135 759 916 2136 747 918 2137 748 919 2138 820 920 2139 752 921 2140 753 922 2141 747 923 2142 592 924 2143 593 925 2144 717 926 2145 774 927 2146 804 928 2147 773 929 2148 779 930 2149 778 931 2150 475 27 2151 771 27 2152 762 27 2153 731 932 2154 727 933 2155 738 934 2156 732 935 2157 731 932 2158 738 934 2159 732 935 2160 738 934 2161 733 936 2162 749 11 2163 745 11 2164 758 937 2165 750 11 2166 749 11 2167 758 937 2168 750 11 2169 758 937 2170 751 359 2171 772 938 2172 802 939 2173 803 940 2174 771 331 2175 770 331 2176 768 941 2177 762 331 2178 771 331 2179 768 941 2180 764 942 2181 765 943 2182 766 944 2183 764 942 2184 766 944 2185 763 945 2186 472 946 2187 770 368 2188 359 370 2189 809 947 2190 721 948 2191 810 949 2192 785 950 2193 786 951 2194 784 952 2195 787 953 2196 785 950 2197 784 952 2198 791 954 2199 788 955 2200 789 956 2201 791 954 2202 789 956 2203 790 957 2204 711 381 2205 791 27 2206 782 382 2207 713 958 2208 711 381 2209 782 382 2210 713 958 2211 712 383 2212 711 381 2213 763 27 2214 782 382 2215 239 959 2216 717 926 2217 815 960 2218 721 948 2219 782 382 2220 783 961 2221 239 959 2222 239 959 2223 762 27 2224 763 27 2225 783 961 2226 591 27 2227 239 959 2228 778 962 2229 779 963 2230 780 964 2231 780 964 2232 777 965 2233 778 962 2234 743 966 2235 740 967 2236 739 968 2237 739 968 2238 742 969 2239 743 966 2240 761 970 2241 756 971 2242 757 972 2243 757 972 2244 760 973 2245 761 970 2246 796 974 2247 798 975 2248 799 976 2249 799 976 2250 797 977 2251 796 974 2252 835 978 2253 838 979 2254 837 980 2255 836 981 2256 825 982 2257 826 983 2258 858 411 2259 856 410 2260 855 984 2261 927 985 2262 905 798 2263 906 100 2264 899 744 2265 909 143 2266 910 415 2267 873 417 2268 849 416 2269 904 325 2270 899 986 2271 880 987 2272 898 988 2273 827 989 2274 825 982 2275 828 990 2276 927 991 2277 892 992 2278 923 993 2279 835 978 2280 826 983 2281 843 994 2282 843 994 2283 865 995 2284 835 978 2285 885 996 2286 925 997 2287 893 998 2288 838 979 2289 865 995 2290 871 999 2291 871 999 2292 822 1000 2293 876 1001 2294 871 999 2295 829 1002 2296 838 979 2297 838 979 2298 835 978 2299 865 995 2300 861 1003 2301 862 751 2302 871 999 2303 871 999 2304 865 995 2305 861 1003 2306 894 1004 2307 878 1005 2308 897 1006 2309 830 1007 2310 884 1008 2311 881 1009 2312 891 1010 2313 890 1011 2314 889 1012 2315 880 987 2316 877 1013 2317 892 992 2318 914 444 2319 912 443 2320 911 1014 2321 875 1015 2322 851 1016 2323 925 328 2324 874 1017 2325 913 294 2326 914 444 2327 902 1018 2328 916 27 2329 915 1019 2330 898 449 2331 900 797 2332 899 744 2333 853 1020 2334 846 1021 2335 852 1022 2336 879 1023 2337 877 1013 2338 880 987 2339 839 1024 2340 828 990 2341 825 982 2342 889 1012 2343 921 1025 2344 898 988 2345 898 988 2346 880 987 2347 889 1012 2348 890 1011 2349 928 1026 2350 921 1025 2351 920 1027 2352 902 1018 2353 915 1019 2354 928 1026 2355 890 1011 2356 883 1028 2357 890 1011 2358 921 1025 2359 889 1012 2360 917 1029 2361 921 1025 2362 928 1026 2363 928 1026 2364 920 1027 2365 917 1029 2366 818 1030 2367 814 1031 2368 815 960 2369 723 1032 2370 712 1033 2371 725 1034 2372 709 1035 2373 716 1036 2374 708 1037 2375 755 470 2376 756 1038 2377 752 1039 2378 718 1040 2379 790 331 2380 789 1041 2381 761 1042 2382 752 1039 2383 756 1038 2384 794 1043 2385 800 1044 2386 799 1045 2387 770 368 2388 358 479 2389 359 370 2390 801 480 2391 791 954 2392 790 957 2393 705 27 2394 783 961 2395 784 27 2396 802 939 2397 735 1046 2398 803 940 2399 790 957 2400 797 483 2401 801 480 2402 360 1047 2403 769 485 2404 473 549 2405 813 1048 2406 793 1049 2407 795 1050 2408 793 1049 2409 820 920 2410 792 1051 2411 821 1052 2412 792 1051 2413 820 920 2414 753 922 2415 821 1052 2416 820 920 2417 733 1053 2418 474 1054 2419 470 1055 2420 787 331 2421 707 331 2422 596 331 2423 800 915 2424 797 977 2425 799 976 2426 897 1056 2427 895 1057 2428 894 1058 2429 923 502 2430 926 1059 2431 927 985 2432 911 1014 2433 896 1060 2434 897 1056 2435 886 1061 2436 899 986 2437 910 1062 2438 919 33 2439 915 33 2440 916 33 2441 883 1028 2442 891 1010 2443 882 1063 2444 860 27 2445 847 1064 2446 859 1065 2447 870 507 2448 867 506 2449 869 1066 2450 845 1067 2451 843 509 2452 846 1021 2453 850 1068 2454 869 1066 2455 849 416 2456 907 1069 2457 875 1015 2458 925 328 2459 720 1070 2460 817 1071 2461 716 1072 2462 722 1073 2463 808 1074 2464 718 1040 2465 712 1033 2466 724 1075 2467 725 1034 2468 718 1040 2469 725 1034 2470 722 1073 2471 725 1034 2472 719 1076 2473 722 1073 2474 781 1077 2475 764 942 2476 763 945 2477 714 1078 2478 709 1035 2479 710 1079 2480 729 523 2481 708 1037 2482 716 1036 2483 784 1080 2484 594 1081 2485 705 1082 2486 733 936 2487 739 1083 2488 737 1084 2489 737 1084 2490 740 1085 2491 734 1086 2492 760 1087 2493 748 919 2494 754 1088 2495 761 1042 2496 754 1088 2497 753 1089 2498 713 1090 2499 765 1091 2500 724 1075 2501 775 1092 2502 776 1093 2503 769 1094 2504 732 1095 2505 469 1096 2506 731 1097 2507 779 930 2508 774 1098 2509 780 1099 2510 751 359 2511 757 472 2512 755 470 2513 795 546 2514 796 545 2515 797 483 2516 798 1100 2517 794 1043 2518 799 1045 2519 769 485 2520 472 946 2521 473 549 2522 470 1055 2523 732 1101 2524 733 1053 2525 813 1048 2526 752 921 2527 812 1102 2528 745 1103 2529 759 1104 2530 758 1105 2531 471 1106 2532 775 1107 2533 360 1047 2534 777 1108 2535 773 929 2536 778 931 2537 743 1109 2538 734 1086 2539 740 1085 2540 713 958 2541 763 27 2542 766 27 2543 785 1110 2544 594 1081 2545 786 1111 2546 805 1112 2547 734 482 2548 802 939 2549 735 1046 2550 804 928 2551 803 940 2552 807 1113 2553 811 1114 2554 808 1074 2555 810 949 2556 715 1115 2557 811 1114 2558 790 331 2559 811 1114 2560 795 1050 2561 811 1114 2562 813 1048 2563 795 1050 2564 816 1116 2565 730 567 2566 817 1071 2567 815 960 2568 715 1115 2569 721 948 2570 804 928 2571 816 1116 2572 717 926 2573 819 1117 2574 720 1070 2575 714 1118 2576 751 1119 2577 714 1118 2578 750 1120 2579 754 1121 2580 706 1122 2581 821 1052 2582 595 1123 2583 748 1124 2584 590 1125 2585 590 1125 2586 747 1126 2587 593 1127 2588 706 1122 2589 794 1128 2590 821 1052 2591 741 1129 2592 727 1130 2593 726 1131 2594 471 1106 2595 737 1132 2596 805 1112 2597 738 1133 2598 742 969 2599 739 968 2600 759 1104 2601 757 972 2602 758 1105 2603 833 1134 2604 831 1135 2605 834 1136 2606 826 983 2607 837 980 2608 836 981 2609 832 1137 2610 893 998 2611 831 1135 2612 827 989 2613 833 1134 2614 834 1136 2615 837 980 2616 829 1002 2617 830 1007 2618 842 1138 2619 840 1139 2620 839 1140 2621 848 27 2622 822 1000 2623 847 1064 2624 822 1000 2625 903 27 2626 902 1018 2627 841 1141 2628 855 984 2629 840 1139 2630 854 1142 2631 852 1022 2632 851 1016 2633 829 1002 2634 876 1001 2635 884 1008 2636 881 1009 2637 849 1143 2638 830 1007 2639 855 1144 2640 832 1137 2641 833 1134 2642 907 1145 2643 886 1061 2644 910 1062 2645 869 1146 2646 836 981 2647 837 980 2648 856 1147 2649 872 1148 2650 832 1137 2651 925 997 2652 831 1135 2653 893 998 2654 828 990 2655 855 1144 2656 833 1134 2657 882 1063 2658 927 991 2659 906 1149 2660 862 751 2661 847 1064 2662 871 999 2663 882 1063 2664 884 1008 2665 883 1028 2666 867 1150 2667 825 982 2668 836 981 2669 888 1151 2670 893 998 2671 872 1148 2672 857 138 2673 874 1017 2674 856 410 2675 863 11 2676 861 11 2677 864 11 2678 865 995 2679 864 1152 2680 861 1003 2681 843 509 2682 866 1153 2683 865 1154 2684 883 1028 2685 876 1001 2686 928 1026 2687 881 1009 2688 906 1149 2689 904 1155 2690 878 1005 2691 911 1156 2692 897 1006 2693 851 1157 2694 834 1136 2695 831 1135 2696 923 993 2697 877 1013 2698 894 1004 2699 914 1158 2700 872 1148 2701 874 1159 2702 928 1026 2703 822 1000 2704 902 1018 2705 788 1160 2706 711 1161 2707 723 1032 2708 743 1109 2709 736 912 2710 735 1162 2711 806 1163 2712 810 949 2713 807 1113 2714 710 1079 2715 750 1164 2716 714 1078 2717 806 1163 2718 764 1165 2719 767 618 2720 723 1032 2721 789 1041 2722 788 1160 2723 793 619 2724 798 1100 2725 796 545 2726 768 941 2727 776 1093 2728 762 331 2729 762 1166 2730 781 1167 2731 763 1168 2732 784 952 2733 800 1044 2734 787 953 2735 804 928 2736 772 938 2737 803 940 2738 773 362 2739 805 1112 2740 802 939 2741 767 618 2742 809 947 2743 806 1163 2744 780 1099 2745 767 1169 2746 781 1077 2747 751 1119 2748 814 1031 2749 819 1117 2750 814 1031 2751 813 1048 2752 715 1115 2753 816 1116 2754 818 1030 2755 815 960 2756 716 1072 2757 730 567 2758 729 1170 2759 724 1075 2760 764 1165 2761 719 1076 2762 596 331 2763 785 1110 2764 787 331 2765 776 1171 2766 780 964 2767 781 1167 2768 887 1172 2769 885 996 2770 888 1151 2771 880 987 2772 891 1010 2773 889 1012 2774 879 1023 2775 887 1172 2776 878 1005 2777 868 626 2778 839 1140 2779 867 506 2780 894 1058 2781 924 627 2782 923 502 2783 898 449 2784 922 628 2785 901 1173 2786 834 1136 2787 846 1174 2788 827 989 2789 863 11 2790 859 11 2791 862 11 2792 906 100 2793 873 99 2794 904 101 2795 910 415 2796 908 1175 2797 907 1069 2798 917 33 2799 919 33 2800 918 33 2801 921 1025 2802 918 631 2803 922 328 2804 911 1156 2805 888 1151 2806 914 1158 2807 869 1146 2808 830 1007 2809 849 1143 2810 719 1076 2811 807 1113 2812 722 1073 2813 762 27 2814 239 959 2815 475 27 2816 846 1174 2817 826 983 2818 827 989 2819 931 1176 2820 960 1177 2821 932 1178 2822 970 1179 2823 968 1179 2824 969 1179 2825 961 1180 2826 996 1181 2827 960 1177 2828 967 1182 2829 965 1183 2830 966 1184 2831 968 1185 2832 974 1185 2833 969 1185 2834 986 1186 2835 984 1186 2836 985 1186 2837 936 1187 2838 961 1188 2839 931 1189 2840 956 1190 2841 933 40 2842 930 40 2843 942 11 2844 952 1191 2845 953 1191 2846 984 1192 2847 989 1192 2848 985 1192 2849 954 1193 2850 990 1194 2851 991 1195 2852 992 1196 2853 952 1191 2854 993 1197 2855 983 1198 2856 991 1198 2857 963 1198 2858 958 27 2859 984 27 2860 987 27 2861 955 1199 2862 947 1200 2863 994 1201 2864 951 1202 2865 939 1202 2866 950 1202 2867 949 1203 2868 944 1204 2869 959 1205 2870 977 1206 2871 965 1207 2872 976 1208 2873 948 1209 2874 958 1210 2875 988 1211 2876 953 1212 2877 994 1213 2878 959 1214 2879 947 1200 2880 959 1205 2881 994 1201 2882 996 1181 2883 966 1215 2884 977 1206 2885 929 27 2886 934 27 2887 949 27 2888 937 1216 2889 962 1217 2890 936 1187 2891 974 1218 2892 972 1218 2893 973 1218 2894 981 1219 2895 973 1219 2896 980 1219 2897 973 1220 2898 951 1220 2899 950 1220 2900 971 1221 2901 975 1221 2902 968 1221 2903 965 1222 2904 971 1222 2905 970 1222 2906 942 1223 2907 959 1214 2908 944 1224 2909 945 1225 2910 950 1225 2911 939 1225 2912 951 1226 2913 946 1226 2914 940 1226 2915 989 1227 2916 935 1227 2917 929 1227 2918 988 1228 2919 987 1228 2920 986 1228 2921 990 1194 2922 963 1229 2923 991 1195 2924 989 328 2925 986 328 2926 985 328 2927 991 328 2928 952 328 2929 954 328 2930 994 1213 2931 956 1230 2932 955 1231 2933 995 1232 2934 962 1217 2935 990 1194 2936 979 1233 2937 969 1233 2938 978 1233 2939 957 1234 2940 958 1235 2941 930 1236 2942 976 1237 2943 970 1237 2944 979 1237 2945 969 1238 2946 981 1238 2947 978 1238 2948 941 1239 2949 954 1239 2950 952 1239 2951 967 1182 2952 995 1232 2953 990 1194 2954 943 1240 2955 975 1240 2956 964 1240 2957 943 1241 2958 972 1241 2959 975 1241 2960 943 1242 2961 946 1242 2962 972 1242 2963 956 1190 2964 993 1197 2965 983 1243 2966 989 1244 2967 948 1209 2968 988 1211 2969 954 1193 2970 964 1245 2971 967 1182 2972 980 1246 2973 950 1246 2974 982 1246 2975 933 328 2976 963 328 2977 937 328 2978 931 1247 2979 1019 1248 2980 1020 1249 2981 1029 1250 2982 1027 1250 2983 1030 1250 2984 1055 1251 2985 1020 1249 2986 1019 1248 2987 1024 1252 2988 1026 1253 2989 1025 1254 2990 1027 1255 2991 1033 1255 2992 1034 1255 2993 1045 40 2994 1043 40 2995 1046 40 2996 936 1187 2997 1020 1256 2998 1021 1257 2999 933 40 3000 1015 1258 3001 930 40 3002 1011 1259 3003 1001 33 3004 1012 1260 3005 1043 1261 3006 1048 1261 3007 1016 1261 3008 1013 1262 3009 1049 1263 3010 1026 1253 3011 1011 1259 3012 1051 1264 3013 1052 1265 3014 1050 1266 3015 1042 1266 3016 1022 1266 3017 1043 27 3018 1017 27 3019 1046 27 3020 1014 1267 3021 1006 1268 3022 1007 1269 3023 1010 1270 3024 998 1270 3025 999 1270 3026 1008 1271 3027 1003 1272 3028 997 1273 3029 1036 1274 3030 1024 1275 3031 1025 1276 3032 1007 1269 3033 1017 1277 3034 1014 1267 3035 1053 1278 3036 1012 1279 3037 1018 1280 3038 1018 1281 3039 1006 1268 3040 1053 1282 3041 1055 1251 3042 1025 1276 3043 1054 1283 3044 929 27 3045 1007 27 3046 1008 27 3047 1021 1257 3048 937 1216 3049 936 1187 3050 1033 1284 3051 1031 1284 3052 1034 1284 3053 1040 1285 3054 1032 1285 3055 1033 1285 3056 1010 1286 3057 1032 1286 3058 1009 1286 3059 1030 1287 3060 1034 1287 3061 1023 1287 3062 1030 1288 3063 1024 1288 3064 1029 1288 3065 1001 1289 3066 1018 1280 3067 1012 1279 3068 1004 1290 3069 1009 1290 3070 1041 1290 3071 1010 1291 3072 1005 1291 3073 1031 1291 3074 1048 1292 3075 935 1292 3076 1016 1292 3077 1046 1293 3078 1047 1293 3079 1045 1293 3080 1022 1294 3081 1049 1263 3082 1050 1295 3083 1045 328 3084 1048 328 3085 1044 328 3086 1050 328 3087 1011 328 3088 1052 328 3089 1053 1278 3090 1015 1296 3091 1051 1297 3092 1021 1257 3093 1054 1298 3094 1049 1263 3095 1038 1299 3096 1028 1299 3097 1029 1299 3098 1017 1300 3099 1016 1301 3100 930 1302 3101 1029 1303 3102 1035 1303 3103 1038 1303 3104 1028 1304 3105 1040 1304 3106 1033 1304 3107 1000 328 3108 1013 328 3109 1002 328 3110 1026 1253 3111 1054 1298 3112 1025 1254 3113 1002 1305 3114 1023 1305 3115 1034 1305 3116 1002 1306 3117 1034 1306 3118 1031 1306 3119 1002 1307 3120 1031 1307 3121 1005 1307 3122 1052 1265 3123 1015 1258 3124 1042 1308 3125 1048 1309 3126 1007 1269 3127 929 1310 3128 1023 1311 3129 1013 1262 3130 1026 1253 3131 1009 1312 3132 1039 1312 3133 1041 1312 3134 933 328 3135 1022 328 3136 1042 328 3137 1058 1313 3138 1077 1314 3139 1078 1315 3140 1087 1316 3141 1085 1316 3142 1088 1316 3143 1113 1317 3144 1078 1315 3145 1077 1314 3146 1082 1318 3147 1084 1319 3148 1083 1320 3149 1085 1321 3150 1091 1321 3151 1092 1321 3152 1103 331 3153 1101 331 3154 1104 331 3155 1062 1322 3156 1078 1323 3157 1079 1324 3158 1060 331 3159 1073 1325 3160 1057 331 3161 1069 1326 3162 942 11 3163 1070 1327 3164 1101 1328 3165 1106 1328 3166 1074 1328 3167 1071 1329 3168 1107 1330 3169 1084 1319 3170 1069 1326 3171 1109 1331 3172 1110 1332 3173 1108 1333 3174 1100 1333 3175 1080 1333 3176 1101 27 3177 1075 27 3178 1104 27 3179 1072 1334 3180 1064 1335 3181 1065 1336 3182 1068 1337 3183 939 1337 3184 940 1337 3185 1066 1338 3186 944 1204 3187 938 1339 3188 1094 1340 3189 1082 1341 3190 1083 1342 3191 1065 1336 3192 1075 1343 3193 1072 1334 3194 1111 1344 3195 1070 1345 3196 1076 1346 3197 1076 1347 3198 1064 1335 3199 1111 1348 3200 1113 1317 3201 1083 1342 3202 1112 1349 3203 1056 27 3204 1065 27 3205 1066 27 3206 1079 1324 3207 1063 1350 3208 1062 1322 3209 1091 1351 3210 1089 1351 3211 1092 1351 3212 1098 1352 3213 1090 1352 3214 1091 1352 3215 1068 1353 3216 1090 1353 3217 1067 1353 3218 1088 1354 3219 1092 1354 3220 1081 1354 3221 1088 1355 3222 1082 1355 3223 1087 1355 3224 942 1223 3225 1076 1346 3226 1070 1345 3227 945 1356 3228 1067 1356 3229 1099 1356 3230 1068 1357 3231 946 1357 3232 1089 1357 3233 1106 1358 3234 1061 1358 3235 1074 1358 3236 1104 1228 3237 1105 1228 3238 1103 1228 3239 1080 1359 3240 1107 1330 3241 1108 1360 3242 1103 328 3243 1106 328 3244 1102 328 3245 1108 328 3246 1069 328 3247 1110 328 3248 1111 1344 3249 1073 1361 3250 1109 1362 3251 1079 1324 3252 1112 1363 3253 1107 1330 3254 1096 1364 3255 1086 1364 3256 1087 1364 3257 1075 1365 3258 1074 1366 3259 1057 1367 3260 1087 1368 3261 1093 1368 3262 1096 1368 3263 1086 1369 3264 1098 1369 3265 1091 1369 3266 941 328 3267 1071 328 3268 943 328 3269 1084 1319 3270 1112 1363 3271 1083 1320 3272 943 1240 3273 1081 1240 3274 1092 1240 3275 943 1241 3276 1092 1241 3277 1089 1241 3278 943 1242 3279 1089 1242 3280 946 1242 3281 1110 1332 3282 1073 1325 3283 1100 1370 3284 1106 1371 3285 1065 1336 3286 1056 1372 3287 1081 1373 3288 1071 1329 3289 1084 1319 3290 1067 1374 3291 1097 1374 3292 1099 1374 3293 1060 328 3294 1080 328 3295 1100 328 3296 1058 1375 3297 1127 1376 3298 1059 1375 3299 1137 1377 3300 1135 1377 3301 1136 1377 3302 1128 1378 3303 1163 1379 3304 1127 1376 3305 1134 1380 3306 1132 1381 3307 1133 1382 3308 1135 1383 3309 1141 1383 3310 1136 1383 3311 1153 1384 3312 1151 1384 3313 1152 1384 3314 1062 1322 3315 1128 1385 3316 1058 1386 3317 1123 1387 3318 1060 331 3319 1057 331 3320 1001 33 3321 1119 1388 3322 1120 1388 3323 1151 1389 3324 1156 1389 3325 1152 1389 3326 1121 1390 3327 1157 1391 3328 1158 1392 3329 1159 1393 3330 1119 1388 3331 1160 1394 3332 1150 1395 3333 1158 1395 3334 1130 1395 3335 1125 27 3336 1151 27 3337 1154 27 3338 1122 1396 3339 1114 1397 3340 1161 1398 3341 1118 1399 3342 998 1399 3343 1117 1399 3344 1116 1400 3345 1003 1272 3346 1126 1401 3347 1144 1402 3348 1132 1403 3349 1143 1404 3350 1115 1405 3351 1125 1406 3352 1155 1407 3353 1120 1408 3354 1161 1409 3355 1126 1410 3356 1114 1397 3357 1126 1401 3358 1161 1398 3359 1163 1379 3360 1133 1411 3361 1144 1402 3362 1056 27 3363 934 27 3364 1116 27 3365 1063 1350 3366 1129 1412 3367 1062 1322 3368 1141 1413 3369 1139 1413 3370 1140 1413 3371 1148 1414 3372 1140 1414 3373 1147 1414 3374 1140 1415 3375 1118 1415 3376 1117 1415 3377 1138 1416 3378 1142 1416 3379 1135 1416 3380 1132 1417 3381 1138 1417 3382 1137 1417 3383 1001 1418 3384 1126 1410 3385 1003 1419 3386 1004 1420 3387 1117 1420 3388 998 1420 3389 1118 1421 3390 1005 1421 3391 999 1421 3392 1156 1422 3393 1061 1422 3394 1056 1422 3395 1155 1293 3396 1154 1293 3397 1153 1293 3398 1157 1391 3399 1130 1423 3400 1158 1392 3401 1156 328 3402 1153 328 3403 1152 328 3404 1158 328 3405 1119 328 3406 1121 328 3407 1161 1409 3408 1123 1424 3409 1122 1425 3410 1162 1426 3411 1129 1412 3412 1157 1391 3413 1146 1427 3414 1136 1427 3415 1145 1427 3416 1124 1428 3417 1125 1429 3418 1057 1430 3419 1143 1431 3420 1137 1431 3421 1146 1431 3422 1136 1432 3423 1148 1432 3424 1145 1432 3425 1000 1433 3426 1121 1433 3427 1119 1433 3428 1134 1380 3429 1162 1426 3430 1157 1391 3431 1002 1434 3432 1142 1434 3433 1131 1434 3434 1002 1435 3435 1139 1435 3436 1142 1435 3437 1002 1436 3438 1005 1436 3439 1139 1436 3440 1123 1387 3441 1160 1394 3442 1150 1437 3443 1156 1438 3444 1115 1405 3445 1155 1407 3446 1121 1390 3447 1131 1439 3448 1134 1380 3449 1147 1440 3450 1117 1440 3451 1149 1440 3452 1060 328 3453 1130 328 3454 1063 328 3455 34 5 3456 33 0 3457 22 4 3458 75 7 3459 74 1441 3460 93 8 3461 112 15 3462 104 242 3463 44 16 3464 39 18 3465 38 1442 3466 117 19 3467 9 21 3468 101 50 3469 66 22 3470 65 24 3471 64 1443 3472 71 25 3473 243 27 3474 116 27 3475 63 27 3476 64 36 3477 65 314 3478 94 37 3479 240 47 3480 60 1444 3481 62 48 3482 101 50 3483 9 21 3484 13 51 3485 9 21 3486 108 257 3487 107 66 3488 160 90 3489 159 294 3490 158 91 3491 229 93 3492 228 192 3493 207 94 3494 201 96 3495 202 142 3496 211 97 3497 175 99 3498 152 204 3499 151 100 3500 201 102 3501 181 146 3502 182 103 3503 129 105 3504 128 89 3505 127 88 3506 229 107 3507 193 127 3508 194 108 3509 187 112 3510 209 287 3511 227 113 3512 173 115 3513 149 197 3514 124 116 3515 196 121 3516 179 130 3517 180 122 3518 132 124 3519 131 118 3520 186 125 3521 216 131 3522 215 138 3523 214 132 3524 177 134 3525 156 284 3526 153 135 3527 176 137 3528 126 1445 3529 215 138 3530 204 139 3531 205 27 3532 218 27 3533 200 141 3534 203 322 3535 202 142 3536 155 143 3537 147 202 3538 148 144 3539 181 146 3540 180 122 3541 179 130 3542 141 147 3543 142 1446 3544 130 106 3545 222 150 3546 230 149 3547 204 139 3548 110 153 3549 111 259 3550 106 154 3551 15 155 3552 3 304 3553 4 156 3554 1 158 3555 12 1447 3556 8 159 3557 47 161 3558 49 237 3559 48 162 3560 10 164 3561 100 210 3562 82 165 3563 53 167 3564 45 226 3565 44 163 3566 86 168 3567 79 56 3568 92 169 3569 62 48 3570 63 1448 3571 116 171 3572 93 172 3573 74 33 3574 83 57 3575 232 27 3576 115 27 3577 75 67 3578 94 37 3579 26 253 3580 27 173 3581 82 60 3582 87 238 3583 89 174 3584 123 175 3585 67 247 3586 61 176 3587 105 178 3588 104 242 3589 85 179 3590 85 179 3591 104 242 3592 112 15 3593 113 182 3594 86 270 3595 84 181 3596 45 17 3597 46 263 3598 113 182 3599 25 183 3600 29 274 3601 242 184 3602 79 186 3603 86 270 3604 234 187 3605 93 8 3606 89 83 3607 91 82 3608 199 188 3609 198 193 3610 197 189 3611 225 191 3612 226 320 3613 228 192 3614 213 133 3615 214 132 3616 198 193 3617 188 194 3618 181 146 3619 201 102 3620 221 11 3621 222 11 3622 217 11 3623 185 151 3624 192 128 3625 193 127 3626 162 27 3627 150 27 3628 149 197 3629 172 199 3630 170 319 3631 169 200 3632 147 202 3633 146 884 3634 145 203 3635 152 204 3636 172 199 3637 171 201 3638 209 205 3639 210 326 3640 177 134 3641 12 206 3642 110 153 3643 109 207 3644 14 209 3645 99 254 3646 100 210 3647 4 156 3648 5 227 3649 16 211 3650 10 164 3651 15 155 3652 17 157 3653 17 157 3654 16 211 3655 11 212 3656 73 213 3657 59 315 3658 56 43 3659 6 214 3660 12 1447 3661 1 158 3662 21 216 3663 20 811 3664 0 160 3665 76 217 3666 78 251 3667 119 218 3668 25 32 3669 30 30 3670 31 220 3671 29 221 3672 31 220 3673 32 222 3674 52 224 3675 51 10 3676 40 14 3677 53 167 3678 52 224 3679 46 225 3680 5 227 3681 58 821 3682 57 228 3683 67 229 3684 69 248 3685 68 230 3686 24 232 3687 235 1449 3688 236 233 3689 71 25 3690 64 1443 3691 66 235 3692 43 35 3693 50 34 3694 49 237 3695 87 238 3696 85 310 3697 88 239 3698 90 240 3699 84 832 3700 86 168 3701 61 176 3702 60 1444 3703 240 47 3704 237 185 3705 235 1450 3706 24 241 3707 105 178 3708 47 1451 3709 44 16 3710 37 243 3711 36 1452 3712 51 244 3713 238 246 3714 97 252 3715 67 247 3716 69 248 3717 67 229 3718 65 24 3719 35 249 3720 27 305 3721 26 223 3722 5 63 3723 74 62 3724 55 27 3725 77 250 3726 231 1453 3727 119 218 3728 97 252 3729 29 274 3730 26 253 3731 27 173 3732 28 1454 3733 96 23 3734 99 254 3735 102 52 3736 103 255 3737 102 52 3738 13 51 3739 7 256 3740 82 165 3741 100 210 3742 103 255 3743 103 255 3744 7 256 3745 105 178 3746 108 257 3747 28 1454 3748 22 258 3749 107 66 3750 106 154 3751 7 256 3752 96 23 3753 28 1454 3754 108 257 3755 111 259 3756 110 153 3757 12 206 3758 43 261 3759 111 259 3760 6 260 3761 46 263 3762 120 265 3763 233 264 3764 120 265 3765 46 263 3766 40 266 3767 114 267 3768 40 266 3769 39 268 3770 233 264 3771 234 187 3772 86 270 3773 33 271 3774 30 275 3775 19 272 3776 238 246 3777 242 184 3778 29 274 3779 30 275 3780 33 271 3781 34 75 3782 51 244 3783 52 79 3784 49 78 3785 135 276 3786 134 279 3787 133 277 3788 128 89 3789 137 84 3790 139 86 3791 134 279 3792 174 290 3793 195 114 3794 129 105 3795 130 106 3796 135 276 3797 139 86 3798 140 85 3799 131 118 3800 144 280 3801 143 283 3802 142 281 3803 150 27 3804 125 27 3805 124 116 3806 124 116 3807 125 27 3808 205 27 3809 143 283 3810 160 90 3811 157 92 3812 156 284 3813 155 143 3814 154 145 3815 131 118 3816 173 115 3817 178 117 3818 183 126 3819 206 298 3820 151 285 3821 157 286 3822 158 289 3823 134 279 3824 209 287 3825 187 112 3826 188 194 3827 171 288 3828 169 292 3829 138 87 3830 158 289 3831 176 302 3832 174 290 3833 227 113 3834 153 300 3835 133 277 3836 130 106 3837 142 1446 3838 157 286 3839 184 196 3840 193 127 3841 229 107 3842 164 120 3843 161 198 3844 149 197 3845 184 196 3846 183 126 3847 186 125 3848 169 292 3849 141 147 3850 127 88 3851 190 293 3852 187 112 3853 195 114 3854 159 294 3855 126 1445 3856 176 137 3857 165 33 3858 164 33 3859 163 33 3860 167 111 3861 168 328 3862 166 295 3863 145 203 3864 146 884 3865 168 296 3866 185 151 3867 186 125 3868 178 117 3869 183 126 3870 184 196 3871 208 291 3872 180 122 3873 189 318 3874 213 299 3875 153 300 3876 154 1455 3877 136 278 3878 225 109 3879 194 108 3880 179 130 3881 216 301 3882 190 293 3883 174 290 3884 230 149 3885 178 117 3886 124 116 3887 80 303 3888 83 1456 3889 3 304 3890 35 249 3891 34 5 3892 28 6 3893 98 306 3894 101 50 3895 102 52 3896 2 215 3897 41 1457 3898 42 307 3899 98 306 3900 11 212 3901 56 308 3902 15 155 3903 10 164 3904 81 166 3905 85 310 3906 84 832 3907 90 240 3908 60 41 3909 61 231 3910 68 230 3911 54 311 3912 68 317 3913 73 312 3914 76 55 3915 75 11 3916 92 169 3917 96 23 3918 66 22 3919 64 36 3920 65 314 3921 67 247 3922 97 252 3923 59 309 3924 66 22 3925 101 50 3926 72 236 3927 66 235 3928 59 315 3929 43 261 3930 47 1451 3931 106 154 3932 106 154 3933 47 1451 3934 105 178 3935 108 257 3936 109 207 3937 110 153 3938 8 208 3939 109 207 3940 22 258 3941 16 211 3942 57 228 3943 56 308 3944 121 40 3945 231 1453 3946 77 250 3947 68 317 3948 69 71 3949 72 70 3950 189 318 3951 188 194 3952 187 112 3953 182 103 3954 194 108 3955 193 127 3956 181 146 3957 188 194 3958 189 318 3959 170 319 3960 144 280 3961 141 282 3962 196 190 3963 197 189 3964 226 320 3965 200 141 3966 223 906 3967 224 321 3968 136 278 3969 154 1455 3970 148 323 3971 165 33 3972 162 33 3973 161 33 3974 208 95 3975 207 94 3976 175 324 3977 212 98 3978 211 97 3979 210 326 3980 219 11 3981 222 11 3982 221 11 3983 223 148 3984 219 152 3985 220 327 3986 213 299 3987 189 318 3988 190 293 3989 171 288 3990 139 86 3991 132 124 3992 11 212 3993 98 306 3994 99 254 3995 148 323 3996 145 110 3997 128 89 3998 278 333 3999 272 612 4000 266 4 4001 337 334 4002 318 1458 4003 319 335 4004 356 341 4005 289 493 4006 288 342 4007 117 344 4008 282 1459 4009 283 345 4010 253 347 4011 340 562 4012 310 348 4013 315 350 4014 308 544 4015 309 351 4016 307 27 4017 358 27 4018 475 27 4019 308 360 4020 339 940 4021 338 361 4022 306 368 4023 304 1460 4024 472 369 4025 257 371 4026 253 347 4027 345 349 4028 253 347 4029 257 371 4030 351 385 4031 395 410 4032 396 601 4033 397 411 4034 444 413 4035 465 501 4036 466 414 4037 448 143 4038 439 202 4039 438 144 4040 388 416 4041 389 511 4042 412 417 4043 438 418 4044 437 456 4045 419 419 4046 366 421 4047 367 454 4048 364 409 4049 466 422 4050 462 609 4051 431 423 4052 464 427 4053 446 595 4054 424 428 4055 410 430 4056 415 589 4057 361 431 4058 433 436 4059 436 1461 4060 417 437 4061 369 439 4062 420 590 4063 423 440 4064 451 443 4065 452 294 4066 453 444 4067 390 446 4068 393 588 4069 414 447 4070 452 294 4071 363 27 4072 413 27 4073 455 27 4074 442 27 4075 441 432 4076 439 202 4077 440 1173 4078 437 449 4079 385 450 4080 384 510 4081 392 451 4082 418 420 4083 419 419 4084 416 438 4085 378 453 4086 364 409 4087 367 454 4088 459 435 4089 454 448 4090 441 432 4091 354 461 4092 351 385 4093 350 462 4094 259 464 4095 261 518 4096 248 465 4097 245 467 4098 244 524 4099 252 468 4100 291 470 4101 288 475 4102 292 471 4103 326 473 4104 344 515 4105 254 474 4106 288 475 4107 289 1089 4108 297 476 4109 330 477 4110 335 1462 4111 336 478 4112 358 479 4113 307 1463 4114 306 368 4115 337 480 4116 326 380 4117 327 377 4118 232 27 4119 320 27 4120 319 387 4121 338 361 4122 339 940 4123 271 481 4124 333 483 4125 331 546 4126 326 380 4127 360 484 4128 473 549 4129 305 485 4130 329 487 4131 348 343 4132 349 488 4133 329 487 4134 328 491 4135 356 341 4136 357 490 4137 356 341 4138 328 491 4139 289 493 4140 356 341 4141 357 490 4142 474 495 4143 273 561 4144 269 496 4145 234 40 4146 330 492 4147 323 40 4148 336 336 4149 335 401 4150 333 403 4151 434 498 4152 435 503 4153 436 499 4154 465 501 4155 463 627 4156 462 502 4157 435 503 4158 451 443 4159 450 445 4160 425 504 4161 449 1464 4162 438 418 4163 458 33 4164 455 33 4165 454 33 4166 430 424 4167 429 442 4168 422 459 4169 386 432 4170 387 27 4171 399 27 4172 406 506 4173 407 626 4174 409 507 4175 382 509 4176 383 322 4177 384 510 4178 408 508 4179 409 507 4180 389 511 4181 414 447 4182 447 630 4183 446 512 4184 256 513 4185 252 624 4186 353 514 4187 344 515 4188 343 565 4189 258 516 4190 260 517 4191 249 534 4192 248 465 4193 254 474 4194 258 516 4195 261 518 4196 255 519 4197 260 517 4198 261 518 4199 317 520 4200 299 367 4201 300 364 4202 250 522 4203 246 614 4204 245 467 4205 265 523 4206 252 468 4207 244 524 4208 320 526 4209 232 1465 4210 119 527 4211 269 357 4212 273 530 4213 275 529 4214 273 530 4215 270 558 4216 276 531 4217 296 532 4218 290 533 4219 284 340 4220 297 476 4221 289 1089 4222 290 533 4223 249 534 4224 260 517 4225 301 535 4226 312 537 4227 313 557 4228 311 538 4229 469 540 4230 468 1466 4231 268 541 4232 315 350 4233 316 623 4234 310 543 4235 287 359 4236 291 470 4237 293 472 4238 332 545 4239 329 619 4240 331 546 4241 334 547 4242 335 1462 4243 330 477 4244 472 369 4245 304 1460 4246 305 485 4247 268 550 4248 468 1467 4249 470 497 4250 349 488 4251 348 343 4252 288 342 4253 295 552 4254 280 1452 4255 281 553 4256 471 555 4257 360 484 4258 311 486 4259 313 557 4260 314 352 4261 309 351 4262 270 558 4263 271 1468 4264 279 559 4265 249 381 4266 302 27 4267 299 27 4268 119 527 4269 231 1469 4270 321 560 4271 341 556 4272 338 361 4273 270 482 4274 271 481 4275 339 940 4276 340 562 4277 347 564 4278 346 372 4279 343 565 4280 251 566 4281 257 371 4282 346 372 4283 326 473 4284 331 489 4285 347 564 4286 349 488 4287 251 566 4288 347 564 4289 352 386 4290 353 514 4291 266 567 4292 351 385 4293 257 371 4294 251 566 4295 352 386 4296 272 563 4297 340 562 4298 355 463 4299 250 569 4300 256 513 4301 287 568 4302 286 1470 4303 250 569 4304 233 570 4305 120 571 4306 290 494 4307 120 571 4308 114 574 4309 284 572 4310 283 573 4311 284 572 4312 114 574 4313 233 570 4314 357 490 4315 330 492 4316 263 576 4317 274 579 4318 277 577 4319 471 555 4320 341 556 4321 273 561 4322 274 579 4323 275 393 4324 278 395 4325 293 397 4326 296 399 4327 295 552 4328 372 580 4329 373 607 4330 370 581 4331 365 408 4332 375 407 4333 376 405 4334 371 582 4335 370 581 4336 432 429 4337 366 421 4338 373 607 4339 372 580 4340 368 433 4341 377 406 4342 376 405 4343 379 584 4344 380 587 4345 381 585 4346 361 431 4347 362 27 4348 387 27 4349 442 27 4350 362 27 4351 361 431 4352 394 412 4353 397 411 4354 380 587 4355 391 452 4356 392 451 4357 393 588 4358 368 433 4359 423 440 4360 415 589 4361 420 590 4362 369 439 4363 388 591 4364 394 593 4365 372 580 4366 371 582 4367 446 595 4368 449 1464 4369 425 504 4370 408 596 4371 376 405 4372 375 407 4373 395 594 4374 371 582 4375 411 583 4376 370 581 4377 390 606 4378 464 427 4379 367 454 4380 372 580 4381 394 593 4382 466 422 4383 430 424 4384 421 505 4385 401 435 4386 410 430 4387 386 432 4388 421 505 4389 422 459 4390 423 440 4391 406 597 4392 375 407 4393 364 409 4394 427 600 4395 411 583 4396 432 429 4397 413 27 4398 363 27 4399 396 601 4400 400 11 4401 401 11 4402 402 11 4403 404 426 4404 400 434 4405 403 602 4406 382 509 4407 404 1154 4408 405 603 4409 422 459 4410 467 458 4411 415 589 4412 420 590 4413 443 592 4414 445 599 4415 417 437 4416 436 1461 4417 450 604 4418 390 606 4419 370 581 4420 373 607 4421 462 609 4422 433 436 4423 416 438 4424 453 610 4425 413 598 4426 411 583 4427 467 458 4428 441 432 4429 361 431 4430 324 303 4431 259 464 4432 247 466 4433 279 559 4434 271 1468 4435 272 612 4436 346 372 4437 345 349 4438 342 613 4439 246 614 4440 250 522 4441 286 615 4442 300 617 4443 255 519 4444 342 613 4445 259 464 4446 324 303 4447 325 166 4448 329 619 4449 332 545 4450 334 547 4451 304 363 4452 298 40 4453 312 537 4454 317 620 4455 312 625 4456 298 621 4457 320 374 4458 323 376 4459 336 478 4460 340 562 4461 339 940 4462 308 360 4463 309 362 4464 338 361 4465 341 556 4466 345 349 4467 310 348 4468 303 618 4469 316 623 4470 317 520 4471 303 521 4472 287 568 4473 355 463 4474 350 462 4475 350 462 4476 251 566 4477 349 488 4478 352 386 4479 351 385 4480 354 461 4481 252 624 4482 265 1170 4483 266 567 4484 260 517 4485 255 519 4486 300 617 4487 321 560 4488 231 1469 4489 121 40 4490 316 389 4491 313 391 4492 312 625 4493 426 605 4494 427 600 4495 424 428 4496 430 424 4497 431 423 4498 419 419 4499 418 420 4500 417 437 4501 426 605 4502 378 586 4503 381 585 4504 407 626 4505 463 627 4506 434 498 4507 433 500 4508 437 449 4509 440 1173 4510 461 628 4511 373 607 4512 366 421 4513 385 629 4514 402 11 4515 401 11 4516 398 11 4517 412 99 4518 444 413 4519 445 100 4520 447 630 4521 448 143 4522 449 415 4523 458 33 4524 459 33 4525 456 33 4526 460 457 4527 461 328 4528 457 631 4529 450 604 4530 453 610 4531 427 600 4532 369 439 4533 376 405 4534 408 596 4535 343 565 4536 342 613 4537 255 519 4538 385 629 4539 366 421 4540 365 408 4541 510 636 4542 504 894 4543 498 635 4544 569 637 4545 550 639 4546 551 638 4547 588 643 4548 521 782 4549 520 644 4550 592 646 4551 514 1471 4552 515 647 4553 485 649 4554 572 845 4555 542 22 4556 547 651 4557 540 829 4558 541 652 4559 539 27 4560 116 27 4561 243 27 4562 540 662 4563 571 1472 4564 570 663 4565 538 48 4566 536 1444 4567 240 671 4568 489 672 4569 485 649 4570 577 650 4571 485 649 4572 489 672 4573 583 687 4574 631 712 4575 632 883 4576 633 90 4577 680 94 4578 701 192 4579 702 93 4580 684 97 4581 675 142 4582 674 96 4583 624 100 4584 625 798 4585 648 99 4586 674 714 4587 673 748 4588 655 715 4589 602 717 4590 603 746 4591 600 711 4592 702 718 4593 698 890 4594 667 719 4595 700 723 4596 682 877 4597 660 724 4598 646 726 4599 651 871 4600 597 727 4601 669 732 4602 672 1473 4603 653 733 4604 605 735 4605 656 872 4606 659 736 4607 687 132 4608 688 138 4609 689 131 4610 626 135 4611 629 870 4612 650 740 4613 688 138 4614 599 1445 4615 649 741 4616 691 27 4617 678 27 4618 677 742 4619 675 142 4620 676 322 4621 673 141 4622 621 744 4623 620 797 4624 628 143 4625 654 716 4626 655 715 4627 652 734 4628 614 745 4629 600 711 4630 603 746 4631 695 751 4632 690 743 4633 677 742 4634 586 754 4635 583 687 4636 582 755 4637 491 757 4638 493 805 4639 480 758 4640 477 760 4641 476 810 4642 484 761 4643 523 763 4644 520 768 4645 524 764 4646 558 765 4647 576 802 4648 486 766 4649 520 768 4650 521 1474 4651 529 769 4652 562 770 4653 567 170 4654 568 771 4655 116 171 4656 539 1448 4657 538 48 4658 569 172 4659 558 681 4660 559 678 4661 705 27 4662 552 27 4663 551 689 4664 570 663 4665 571 1472 4666 503 772 4667 565 174 4668 563 830 4669 558 681 4670 123 774 4671 241 177 4672 537 176 4673 561 776 4674 580 645 4675 581 777 4676 561 776 4677 560 780 4678 588 643 4679 589 779 4680 588 643 4681 560 780 4682 521 782 4683 588 643 4684 589 779 4685 242 784 4686 505 844 4687 501 785 4688 707 787 4689 562 781 4690 555 788 4691 567 703 4692 565 705 4693 569 637 4694 670 789 4695 671 792 4696 672 790 4697 701 192 4698 699 320 4699 698 191 4700 671 792 4701 687 132 4702 686 739 4703 661 793 4704 685 1475 4705 674 714 4706 694 11 4707 691 11 4708 690 11 4709 666 720 4710 665 738 4711 658 752 4712 622 728 4713 623 27 4714 635 27 4715 642 200 4716 643 905 4717 645 199 4718 618 796 4719 619 884 4720 620 797 4721 644 201 4722 645 199 4723 625 798 4724 650 740 4725 683 326 4726 682 799 4727 488 800 4728 484 903 4729 585 801 4730 576 802 4731 575 848 4732 490 803 4733 492 804 4734 481 819 4735 480 758 4736 486 766 4737 490 803 4738 493 805 4739 487 806 4740 492 804 4741 493 805 4742 549 807 4743 531 670 4744 532 667 4745 482 809 4746 478 896 4747 477 760 4748 497 216 4749 484 761 4750 476 810 4751 552 812 4752 705 1476 4753 594 813 4754 501 658 4755 505 816 4756 507 815 4757 505 816 4758 502 841 4759 508 817 4760 528 224 4761 522 818 4762 516 14 4763 529 769 4764 521 1474 4765 522 818 4766 481 819 4767 492 804 4768 533 820 4769 544 822 4770 545 840 4771 543 823 4772 236 825 4773 235 1449 4774 500 826 4775 547 651 4776 548 902 4777 542 828 4778 519 35 4779 523 763 4780 525 237 4781 564 239 4782 561 310 4783 563 830 4784 566 831 4785 567 170 4786 562 770 4787 240 671 4788 536 1444 4789 537 176 4790 500 833 4791 235 1450 4792 237 786 4793 581 777 4794 580 645 4795 520 644 4796 527 835 4797 512 1477 4798 513 836 4799 238 838 4800 123 774 4801 543 775 4802 545 840 4803 546 653 4804 541 652 4805 502 841 4806 503 1478 4807 511 842 4808 481 684 4809 534 27 4810 531 27 4811 594 813 4812 704 1479 4813 553 843 4814 573 839 4815 570 663 4816 502 773 4817 503 772 4818 571 1472 4819 572 845 4820 579 847 4821 578 673 4822 575 848 4823 483 849 4824 489 672 4825 578 673 4826 558 765 4827 563 778 4828 579 847 4829 581 777 4830 483 849 4831 579 847 4832 584 688 4833 585 801 4834 498 258 4835 583 687 4836 489 672 4837 483 849 4838 584 688 4839 504 846 4840 572 845 4841 587 756 4842 482 851 4843 488 800 4844 519 850 4845 518 1480 4846 482 851 4847 706 852 4848 595 853 4849 522 783 4850 595 853 4851 590 856 4852 516 854 4853 515 855 4854 516 854 4855 590 856 4856 706 852 4857 589 779 4858 562 781 4859 495 858 4860 506 861 4861 509 859 4862 238 838 4863 573 839 4864 505 844 4865 506 861 4866 507 695 4867 510 697 4868 525 699 4869 528 701 4870 527 835 4871 608 862 4872 609 888 4873 606 863 4874 601 710 4875 611 709 4876 612 707 4877 607 864 4878 606 863 4879 668 725 4880 602 717 4881 609 888 4882 608 862 4883 604 729 4884 613 708 4885 612 707 4886 615 866 4887 616 869 4888 617 867 4889 597 727 4890 598 27 4891 623 27 4892 678 27 4893 598 27 4894 597 727 4895 630 713 4896 633 90 4897 616 869 4898 627 145 4899 628 143 4900 629 870 4901 604 729 4902 659 736 4903 651 871 4904 656 872 4905 605 735 4906 624 873 4907 630 875 4908 608 862 4909 607 864 4910 682 877 4911 685 1475 4912 661 793 4913 644 878 4914 612 707 4915 611 709 4916 631 876 4917 607 864 4918 647 865 4919 606 863 4920 626 887 4921 700 723 4922 603 746 4923 608 862 4924 630 875 4925 702 718 4926 666 720 4927 657 794 4928 637 731 4929 646 726 4930 622 728 4931 657 794 4932 658 752 4933 659 736 4934 642 879 4935 611 709 4936 600 711 4937 663 882 4938 647 865 4939 668 725 4940 649 741 4941 599 1445 4942 632 883 4943 636 33 4944 637 33 4945 638 33 4946 640 722 4947 636 730 4948 639 295 4949 618 796 4950 640 297 4951 641 296 4952 658 752 4953 703 750 4954 651 871 4955 656 872 4956 679 874 4957 681 881 4958 653 733 4959 672 1473 4960 686 885 4961 626 887 4962 606 863 4963 609 888 4964 698 890 4965 669 732 4966 652 734 4967 689 891 4968 649 880 4969 647 865 4970 703 750 4971 677 742 4972 597 727 4973 556 892 4974 491 757 4975 479 759 4976 511 842 4977 503 1478 4978 504 894 4979 578 673 4980 577 650 4981 574 895 4982 478 896 4983 482 809 4984 518 897 4985 532 899 4986 487 806 4987 574 895 4988 491 757 4989 556 892 4990 557 767 4991 561 310 4992 564 239 4993 566 831 4994 536 665 4995 530 666 4996 544 822 4997 549 900 4998 544 904 4999 530 901 5000 552 675 5001 555 677 5002 568 771 5003 572 845 5004 571 1472 5005 540 662 5006 541 314 5007 570 663 5008 573 839 5009 577 650 5010 542 22 5011 535 309 5012 548 902 5013 549 807 5014 535 808 5015 519 850 5016 587 756 5017 582 755 5018 582 755 5019 483 849 5020 581 777 5021 584 688 5022 583 687 5023 586 754 5024 484 903 5025 497 316 5026 498 258 5027 492 804 5028 487 806 5029 532 899 5030 553 843 5031 704 1479 5032 596 331 5033 548 691 5034 545 693 5035 544 904 5036 662 886 5037 663 882 5038 660 724 5039 666 720 5040 667 719 5041 655 715 5042 654 716 5043 653 733 5044 662 886 5045 614 868 5046 617 867 5047 643 905 5048 699 320 5049 670 789 5050 669 791 5051 673 141 5052 676 322 5053 697 321 5054 609 888 5055 602 717 5056 621 907 5057 638 33 5058 637 33 5059 634 33 5060 648 324 5061 680 94 5062 681 95 5063 683 326 5064 684 97 5065 685 98 5066 694 11 5067 695 11 5068 692 11 5069 696 749 5070 697 328 5071 693 327 5072 686 885 5073 689 891 5074 663 882 5075 605 735 5076 612 707 5077 644 878 5078 575 848 5079 574 895 5080 487 806 5081 621 907 5082 602 717 5083 601 710 5084 742 911 5085 741 632 5086 730 910 5087 783 913 5088 782 913 5089 801 914 5090 820 920 5091 812 1102 5092 752 921 5093 747 923 5094 746 1481 5095 592 924 5096 717 926 5097 809 947 5098 774 927 5099 773 929 5100 772 1482 5101 779 930 5102 475 27 5103 358 27 5104 771 27 5105 772 938 5106 773 362 5107 802 939 5108 472 946 5109 768 1460 5110 770 368 5111 809 947 5112 717 926 5113 721 948 5114 717 926 5115 816 1116 5116 815 960 5117 858 411 5118 857 138 5119 856 410 5120 927 985 5121 926 1059 5122 905 798 5123 899 744 5124 900 797 5125 909 143 5126 873 417 5127 850 1068 5128 849 416 5129 899 986 5130 879 1023 5131 880 987 5132 827 989 5133 826 983 5134 825 982 5135 927 991 5136 891 1010 5137 892 992 5138 885 996 5139 907 1145 5140 925 997 5141 871 999 5142 847 1064 5143 822 1000 5144 894 1004 5145 877 1013 5146 878 1005 5147 830 1007 5148 829 1002 5149 884 1008 5150 914 444 5151 913 294 5152 912 443 5153 875 1015 5154 854 1142 5155 851 1016 5156 874 1017 5157 824 1483 5158 913 294 5159 902 1018 5160 903 27 5161 916 27 5162 898 449 5163 901 1173 5164 900 797 5165 853 1020 5166 845 1067 5167 846 1021 5168 879 1023 5169 878 1005 5170 877 1013 5171 839 1024 5172 840 1484 5173 828 990 5174 920 1027 5175 928 1026 5176 902 1018 5177 818 1030 5178 819 1117 5179 814 1031 5180 723 1032 5181 711 1161 5182 712 1033 5183 709 1035 5184 720 1485 5185 716 1036 5186 755 470 5187 757 472 5188 756 1038 5189 718 1040 5190 808 1074 5191 790 331 5192 761 1042 5193 753 1089 5194 752 1039 5195 794 1043 5196 787 953 5197 800 1044 5198 770 368 5199 771 1463 5200 358 479 5201 801 480 5202 782 11 5203 791 954 5204 705 27 5205 591 27 5206 783 961 5207 802 939 5208 734 482 5209 735 1046 5210 790 957 5211 795 546 5212 797 483 5213 360 1047 5214 775 1107 5215 769 485 5216 813 1048 5217 812 1102 5218 793 1049 5219 793 1049 5220 812 1102 5221 820 920 5222 821 1052 5223 794 1128 5224 792 1051 5225 753 922 5226 754 1121 5227 821 1052 5228 733 1053 5229 737 1132 5230 474 1054 5231 787 331 5232 794 1128 5233 707 331 5234 800 915 5235 801 914 5236 797 977 5237 897 1056 5238 896 1060 5239 895 1057 5240 923 502 5241 924 627 5242 926 1059 5243 911 1014 5244 912 443 5245 896 1060 5246 886 1061 5247 879 1023 5248 899 986 5249 919 33 5250 920 33 5251 915 33 5252 883 1028 5253 890 1011 5254 891 1010 5255 860 27 5256 848 27 5257 847 1064 5258 870 507 5259 868 626 5260 867 506 5261 845 1067 5262 844 322 5263 843 509 5264 850 1068 5265 870 507 5266 869 1066 5267 907 1069 5268 908 1175 5269 875 1015 5270 720 1070 5271 818 1030 5272 817 1071 5273 722 1073 5274 807 1113 5275 808 1074 5276 712 1033 5277 713 1090 5278 724 1075 5279 718 1040 5280 723 1032 5281 725 1034 5282 725 1034 5283 724 1075 5284 719 1076 5285 781 1077 5286 767 1169 5287 764 942 5288 714 1078 5289 720 1485 5290 709 1035 5291 729 523 5292 728 525 5293 708 1037 5294 784 1080 5295 786 1111 5296 594 1081 5297 733 936 5298 738 934 5299 739 1083 5300 737 1084 5301 739 1083 5302 740 1085 5303 760 1087 5304 759 916 5305 748 919 5306 761 1042 5307 760 1087 5308 754 1088 5309 713 1090 5310 766 536 5311 765 1091 5312 775 1092 5313 777 1108 5314 776 1093 5315 732 1095 5316 468 1466 5317 469 1096 5318 779 930 5319 772 1482 5320 774 1098 5321 751 359 5322 758 937 5323 757 472 5324 795 546 5325 793 619 5326 796 545 5327 798 1100 5328 792 548 5329 794 1043 5330 769 485 5331 768 1460 5332 472 946 5333 470 1055 5334 468 1467 5335 732 1101 5336 813 1048 5337 755 1486 5338 752 921 5339 745 1103 5340 744 1487 5341 759 1104 5342 471 1106 5343 805 1112 5344 775 1107 5345 777 1108 5346 775 1092 5347 773 929 5348 743 1109 5349 735 1162 5350 734 1086 5351 713 958 5352 782 382 5353 763 27 5354 785 1110 5355 704 1488 5356 594 1081 5357 805 1112 5358 737 1132 5359 734 482 5360 735 1046 5361 736 1489 5362 804 928 5363 807 1113 5364 810 949 5365 811 1114 5366 810 949 5367 721 948 5368 715 1115 5369 790 331 5370 808 1074 5371 811 1114 5372 811 1114 5373 715 1115 5374 813 1048 5375 816 1116 5376 736 1489 5377 730 567 5378 815 960 5379 814 1031 5380 715 1115 5381 804 928 5382 736 1489 5383 816 1116 5384 819 1117 5385 818 1030 5386 720 1070 5387 751 1119 5388 819 1117 5389 714 1118 5390 754 1121 5391 595 1123 5392 706 1122 5393 595 1123 5394 754 1121 5395 748 1124 5396 590 1125 5397 748 1124 5398 747 1126 5399 706 1122 5400 707 331 5401 794 1128 5402 741 1129 5403 738 1133 5404 727 1130 5405 471 1106 5406 474 1054 5407 737 1132 5408 738 1133 5409 741 1129 5410 742 969 5411 759 1104 5412 760 973 5413 757 972 5414 833 1134 5415 832 1137 5416 831 1135 5417 826 983 5418 835 978 5419 837 980 5420 832 1137 5421 872 1148 5422 893 998 5423 827 989 5424 828 990 5425 833 1134 5426 837 980 5427 838 979 5428 829 1002 5429 842 1138 5430 841 1141 5431 840 1139 5432 848 27 5433 823 27 5434 822 1000 5435 822 1000 5436 823 27 5437 903 27 5438 841 1141 5439 858 411 5440 855 984 5441 854 1142 5442 853 1020 5443 852 1022 5444 829 1002 5445 871 999 5446 876 1001 5447 881 1009 5448 904 1155 5449 849 1143 5450 855 1144 5451 856 1147 5452 832 1137 5453 907 1145 5454 885 996 5455 886 1061 5456 869 1146 5457 867 1150 5458 836 981 5459 856 1147 5460 874 1159 5461 872 1148 5462 925 997 5463 851 1157 5464 831 1135 5465 828 990 5466 840 1484 5467 855 1144 5468 882 1063 5469 891 1010 5470 927 991 5471 862 751 5472 859 1065 5473 847 1064 5474 882 1063 5475 881 1009 5476 884 1008 5477 867 1150 5478 839 1024 5479 825 982 5480 888 1151 5481 885 996 5482 893 998 5483 857 138 5484 824 1483 5485 874 1017 5486 863 11 5487 862 11 5488 861 11 5489 865 995 5490 866 328 5491 864 1152 5492 843 509 5493 844 322 5494 866 1153 5495 883 1028 5496 884 1008 5497 876 1001 5498 881 1009 5499 882 1063 5500 906 1149 5501 878 1005 5502 887 1172 5503 911 1156 5504 851 1157 5505 852 1490 5506 834 1136 5507 923 993 5508 892 992 5509 877 1013 5510 914 1158 5511 888 1151 5512 872 1148 5513 928 1026 5514 876 1001 5515 822 1000 5516 788 1160 5517 791 1491 5518 711 1161 5519 743 1109 5520 742 911 5521 736 912 5522 806 1163 5523 809 947 5524 810 949 5525 710 1079 5526 749 1492 5527 750 1164 5528 806 1163 5529 719 1076 5530 764 1165 5531 723 1032 5532 718 1040 5533 789 1041 5534 793 619 5535 792 548 5536 798 1100 5537 768 941 5538 769 1094 5539 776 1093 5540 762 1166 5541 776 1171 5542 781 1167 5543 784 952 5544 783 33 5545 800 1044 5546 804 928 5547 774 927 5548 772 938 5549 773 362 5550 775 1107 5551 805 1112 5552 767 618 5553 774 927 5554 809 947 5555 780 1099 5556 774 1098 5557 767 1169 5558 751 1119 5559 755 1486 5560 814 1031 5561 814 1031 5562 755 1486 5563 813 1048 5564 816 1116 5565 817 1071 5566 818 1030 5567 716 1072 5568 817 1071 5569 730 567 5570 724 1075 5571 765 1091 5572 764 1165 5573 596 331 5574 704 1488 5575 785 1110 5576 776 1171 5577 777 965 5578 780 964 5579 887 1172 5580 886 1061 5581 885 996 5582 880 987 5583 892 992 5584 891 1010 5585 879 1023 5586 886 1061 5587 887 1172 5588 868 626 5589 842 1138 5590 839 1140 5591 894 1058 5592 895 1057 5593 924 627 5594 898 449 5595 921 297 5596 922 628 5597 834 1136 5598 852 1490 5599 846 1174 5600 863 11 5601 860 11 5602 859 11 5603 906 100 5604 905 798 5605 873 99 5606 910 415 5607 909 143 5608 908 1175 5609 917 33 5610 920 33 5611 919 33 5612 921 1025 5613 917 1029 5614 918 631 5615 911 1156 5616 887 1172 5617 888 1151 5618 869 1146 5619 837 980 5620 830 1007 5621 719 1076 5622 806 1163 5623 807 1113 5624 846 1174 5625 843 994 5626 826 983 5627 931 1176 5628 961 1180 5629 960 1177 5630 970 1316 5631 971 1316 5632 968 1316 5633 961 1180 5634 995 1493 5635 996 1181 5636 967 1182 5637 964 1245 5638 965 1183 5639 968 1494 5640 975 1494 5641 974 1494 5642 986 40 5643 987 40 5644 984 40 5645 936 1187 5646 962 1217 5647 961 1188 5648 956 1190 5649 983 1243 5650 933 40 5651 942 11 5652 941 11 5653 952 1191 5654 984 1328 5655 957 1328 5656 989 1328 5657 954 1193 5658 967 1182 5659 990 1194 5660 992 1196 5661 953 1191 5662 952 1191 5663 983 328 5664 993 328 5665 991 328 5666 958 27 5667 957 27 5668 984 27 5669 955 1199 5670 948 1209 5671 947 1200 5672 951 1337 5673 940 1337 5674 939 1337 5675 949 1203 5676 938 1339 5677 944 1204 5678 977 1206 5679 966 1215 5680 965 1207 5681 948 1209 5682 955 1199 5683 958 1210 5684 953 1212 5685 992 1495 5686 994 1213 5687 947 1200 5688 949 1203 5689 959 1205 5690 996 1181 5691 995 1493 5692 966 1215 5693 938 27 5694 949 27 5695 934 27 5696 949 1496 5697 947 1496 5698 948 1496 5699 929 27 5700 949 27 5701 948 27 5702 937 1216 5703 963 1229 5704 962 1217 5705 974 1351 5706 975 1351 5707 972 1351 5708 981 1352 5709 974 1352 5710 973 1352 5711 973 1497 5712 972 1497 5713 951 1497 5714 971 1354 5715 964 1354 5716 975 1354 5717 965 1498 5718 964 1498 5719 971 1498 5720 942 1223 5721 953 1212 5722 959 1214 5723 945 1356 5724 982 1356 5725 950 1356 5726 951 1357 5727 972 1357 5728 946 1357 5729 989 1292 5730 957 1292 5731 935 1292 5732 988 1499 5733 958 1499 5734 987 1499 5735 990 1194 5736 962 1217 5737 963 1229 5738 989 328 5739 988 328 5740 986 328 5741 991 328 5742 993 328 5743 952 328 5744 994 1213 5745 992 1495 5746 956 1230 5747 995 1232 5748 961 1188 5749 962 1217 5750 979 1364 5751 970 1364 5752 969 1364 5753 958 1235 5754 955 1500 5755 956 1501 5756 956 1501 5757 930 1236 5758 958 1235 5759 930 1236 5760 935 1502 5761 957 1234 5762 976 1503 5763 965 1503 5764 970 1503 5765 969 1504 5766 974 1504 5767 981 1504 5768 941 328 5769 943 328 5770 954 328 5771 967 1182 5772 966 1184 5773 995 1232 5774 956 1190 5775 992 1196 5776 993 1197 5777 989 1244 5778 929 1505 5779 948 1209 5780 954 1193 5781 943 1506 5782 964 1245 5783 980 1507 5784 973 1507 5785 950 1507 5786 933 328 5787 983 328 5788 963 328 5789 931 1247 5790 932 1247 5791 1019 1248 5792 1029 1377 5793 1028 1377 5794 1027 1377 5795 1055 1251 5796 1054 1283 5797 1020 1249 5798 1024 1252 5799 1023 1311 5800 1026 1253 5801 1027 1508 5802 1028 1508 5803 1033 1508 5804 1045 1186 5805 1044 1186 5806 1043 1186 5807 936 1187 5808 931 1189 5809 1020 1256 5810 933 40 5811 1042 1308 5812 1015 1258 5813 1011 1259 5814 1000 33 5815 1001 33 5816 1043 1389 5817 1044 1389 5818 1048 1389 5819 1013 1262 5820 1050 1295 5821 1049 1263 5822 1011 1259 5823 1012 1260 5824 1051 1264 5825 1050 1509 5826 1052 1509 5827 1042 1509 5828 1043 27 5829 1016 27 5830 1017 27 5831 1014 1267 5832 1053 1282 5833 1006 1268 5834 1010 1399 5835 1009 1399 5836 998 1399 5837 1008 1271 5838 1018 1281 5839 1003 1272 5840 1036 1274 5841 1035 1510 5842 1024 1275 5843 1007 1269 5844 1047 1511 5845 1017 1277 5846 1053 1278 5847 1051 1297 5848 1012 1279 5849 1018 1281 5850 1008 1271 5851 1006 1268 5852 1055 1251 5853 1036 1274 5854 1025 1276 5855 1006 1512 5856 1008 1512 5857 1007 1512 5858 1008 27 5859 997 27 5860 934 27 5861 929 27 5862 1008 27 5863 934 27 5864 1021 1257 5865 1022 1294 5866 937 1216 5867 1033 1413 5868 1032 1413 5869 1031 1413 5870 1040 1414 5871 1039 1414 5872 1032 1414 5873 1010 1513 5874 1031 1513 5875 1032 1513 5876 1030 1416 5877 1027 1416 5878 1034 1416 5879 1030 1514 5880 1023 1514 5881 1024 1514 5882 1001 1289 5883 1003 1515 5884 1018 1280 5885 1004 1420 5886 998 1420 5887 1009 1420 5888 1010 1421 5889 999 1421 5890 1005 1421 5891 1048 1516 5892 929 1516 5893 935 1516 5894 1046 1517 5895 1017 1517 5896 1047 1517 5897 1022 1294 5898 1021 1257 5899 1049 1263 5900 1045 328 5901 1047 328 5902 1048 328 5903 1050 328 5904 1013 328 5905 1011 328 5906 1053 1278 5907 1014 1518 5908 1015 1296 5909 1021 1257 5910 1020 1256 5911 1054 1298 5912 1038 1427 5913 1037 1427 5914 1028 1427 5915 1015 1519 5916 1014 1500 5917 1017 1300 5918 1016 1301 5919 935 1520 5920 930 1302 5921 1015 1519 5922 1017 1300 5923 930 1302 5924 1029 1521 5925 1024 1521 5926 1035 1521 5927 1028 1522 5928 1037 1522 5929 1040 1522 5930 1000 1433 5931 1011 1433 5932 1013 1433 5933 1026 1253 5934 1049 1263 5935 1054 1298 5936 1052 1265 5937 1051 1264 5938 1015 1258 5939 1048 1309 5940 1047 1511 5941 1007 1269 5942 1023 1311 5943 1002 1523 5944 1013 1262 5945 1009 1524 5946 1032 1524 5947 1039 1524 5948 933 328 5949 937 328 5950 1022 328 5951 1058 1313 5952 1059 1525 5953 1077 1314 5954 1087 1179 5955 1086 1179 5956 1085 1179 5957 1113 1317 5958 1112 1349 5959 1078 1315 5960 1082 1318 5961 1081 1373 5962 1084 1319 5963 1085 1526 5964 1086 1526 5965 1091 1526 5966 1103 1384 5967 1102 1384 5968 1101 1384 5969 1062 1322 5970 1058 1386 5971 1078 1323 5972 1060 331 5973 1100 1370 5974 1073 1325 5975 1069 1326 5976 941 11 5977 942 11 5978 1101 1192 5979 1102 1192 5980 1106 1192 5981 1071 1329 5982 1108 1360 5983 1107 1330 5984 1069 1326 5985 1070 1327 5986 1109 1331 5987 1108 1527 5988 1110 1527 5989 1100 1527 5990 1101 27 5991 1074 27 5992 1075 27 5993 1072 1334 5994 1111 1348 5995 1064 1335 5996 1068 1202 5997 1067 1202 5998 939 1202 5999 1066 1338 6000 1076 1347 6001 944 1204 6002 1094 1340 6003 1093 1528 6004 1082 1341 6005 1065 1336 6006 1105 1529 6007 1075 1343 6008 1111 1344 6009 1109 1362 6010 1070 1345 6011 1076 1347 6012 1066 1338 6013 1064 1335 6014 1113 1317 6015 1094 1340 6016 1083 1342 6017 1064 1530 6018 1066 1530 6019 1065 1530 6020 1066 27 6021 938 27 6022 934 27 6023 1056 27 6024 1066 27 6025 934 27 6026 1079 1324 6027 1080 1359 6028 1063 1350 6029 1091 1218 6030 1090 1218 6031 1089 1218 6032 1098 1219 6033 1097 1219 6034 1090 1219 6035 1068 1531 6036 1089 1531 6037 1090 1531 6038 1088 1221 6039 1085 1221 6040 1092 1221 6041 1088 1532 6042 1081 1532 6043 1082 1532 6044 942 1223 6045 944 1224 6046 1076 1346 6047 945 1225 6048 939 1225 6049 1067 1225 6050 1068 1226 6051 940 1226 6052 946 1226 6053 1106 1533 6054 1056 1533 6055 1061 1533 6056 1104 1534 6057 1075 1534 6058 1105 1534 6059 1080 1359 6060 1079 1324 6061 1107 1330 6062 1103 328 6063 1105 328 6064 1106 328 6065 1108 328 6066 1071 328 6067 1069 328 6068 1111 1344 6069 1072 1535 6070 1073 1361 6071 1079 1324 6072 1078 1323 6073 1112 1363 6074 1096 1233 6075 1095 1233 6076 1086 1233 6077 1073 1536 6078 1072 1537 6079 1075 1365 6080 1074 1366 6081 1061 1367 6082 1057 1367 6083 1073 1536 6084 1075 1365 6085 1057 1367 6086 1087 1538 6087 1082 1538 6088 1093 1538 6089 1086 1539 6090 1095 1539 6091 1098 1539 6092 941 1239 6093 1069 1239 6094 1071 1239 6095 1084 1319 6096 1107 1330 6097 1112 1363 6098 1110 1332 6099 1109 1331 6100 1073 1325 6101 1106 1371 6102 1105 1529 6103 1065 1336 6104 1081 1373 6105 943 1540 6106 1071 1329 6107 1067 1541 6108 1090 1541 6109 1097 1541 6110 1060 328 6111 1063 328 6112 1080 328 6113 1058 1375 6114 1128 1378 6115 1127 1376 6116 1137 1250 6117 1138 1250 6118 1135 1250 6119 1128 1378 6120 1162 1542 6121 1163 1379 6122 1134 1380 6123 1131 1439 6124 1132 1381 6125 1135 1543 6126 1142 1543 6127 1141 1543 6128 1153 331 6129 1154 331 6130 1151 331 6131 1062 1322 6132 1129 1412 6133 1128 1385 6134 1123 1387 6135 1150 1437 6136 1060 331 6137 1001 33 6138 1000 33 6139 1119 1388 6140 1151 1261 6141 1124 1261 6142 1156 1261 6143 1121 1390 6144 1134 1380 6145 1157 1391 6146 1159 1393 6147 1120 1388 6148 1119 1388 6149 1150 328 6150 1160 328 6151 1158 328 6152 1125 27 6153 1124 27 6154 1151 27 6155 1122 1396 6156 1115 1405 6157 1114 1397 6158 1118 1270 6159 999 1270 6160 998 1270 6161 1116 1400 6162 997 1273 6163 1003 1272 6164 1144 1402 6165 1133 1411 6166 1132 1403 6167 1115 1405 6168 1122 1396 6169 1125 1406 6170 1120 1408 6171 1159 1544 6172 1161 1409 6173 1114 1397 6174 1116 1400 6175 1126 1401 6176 1163 1379 6177 1162 1542 6178 1133 1411 6179 997 27 6180 1116 27 6181 934 27 6182 1116 1545 6183 1114 1545 6184 1115 1545 6185 1056 27 6186 1116 27 6187 1115 27 6188 1063 1350 6189 1130 1423 6190 1129 1412 6191 1141 1546 6192 1142 1546 6193 1139 1546 6194 1148 1285 6195 1141 1285 6196 1140 1285 6197 1140 1547 6198 1139 1547 6199 1118 1547 6200 1138 1548 6201 1131 1548 6202 1142 1548 6203 1132 1549 6204 1131 1549 6205 1138 1549 6206 1001 1418 6207 1120 1408 6208 1126 1410 6209 1004 1290 6210 1149 1290 6211 1117 1290 6212 1118 1550 6213 1139 1550 6214 1005 1550 6215 1156 1358 6216 1124 1358 6217 1061 1358 6218 1155 1551 6219 1125 1551 6220 1154 1551 6221 1157 1391 6222 1129 1412 6223 1130 1423 6224 1156 328 6225 1155 328 6226 1153 328 6227 1158 328 6228 1160 328 6229 1119 328 6230 1161 1409 6231 1159 1544 6232 1123 1424 6233 1162 1426 6234 1128 1385 6235 1129 1412 6236 1146 1299 6237 1137 1299 6238 1136 1299 6239 1125 1429 6240 1122 1537 6241 1123 1552 6242 1123 1552 6243 1057 1430 6244 1125 1429 6245 1057 1430 6246 1061 1553 6247 1124 1428 6248 1143 1554 6249 1132 1554 6250 1137 1554 6251 1136 1555 6252 1141 1555 6253 1148 1555 6254 1000 328 6255 1002 328 6256 1121 328 6257 1134 1380 6258 1133 1382 6259 1162 1426 6260 1123 1387 6261 1159 1393 6262 1160 1394 6263 1156 1438 6264 1056 1556 6265 1115 1405 6266 1121 1390 6267 1002 1557 6268 1131 1439 6269 1147 1558 6270 1140 1558 6271 1117 1558 6272 1060 328 6273 1150 328 6274 1130 328 6275

+ + + + +

106 0 216 107 1 0 110 2 1 110 3 1 111 4 215 106 5 216 98 6 208 99 7 2 14 8 3 14 9 3 11 10 207 98 11 208 110 12 1 107 13 0 108 14 209 108 15 209 109 16 210 110 17 1 99 18 2 100 19 217 10 20 218 10 21 218 14 22 3 99 23 2 4 24 4 17 25 5 15 26 219 15 27 219 3 28 220 4 29 4 5 30 211 16 31 212 17 32 5 17 33 5 4 34 4 5 35 211 17 36 5 14 37 3 10 38 218 10 39 218 15 40 219 17 41 5 16 42 212 11 43 207 14 44 3 14 45 3 17 46 5 16 47 212 8 48 213 0 49 214 1 50 6 1 51 6 12 52 7 8 53 213 1 54 6 2 55 221 6 56 222 6 57 222 12 58 7 1 59 6 0 60 214 8 61 213 21 62 8 21 63 8 20 64 9 0 65 214 495 66 11 496 67 12 23 68 13 23 69 13 24 70 10 495 71 11 33 72 25 18 73 26 20 74 27 33 75 25 20 76 27 21 77 31 33 78 25 21 79 31 22 80 32 22 81 32 28 82 33 34 83 34 34 84 34 33 85 25 22 86 32 28 87 33 27 88 35 35 89 36 35 90 36 34 91 34 28 92 33 27 93 35 26 94 37 32 95 38 32 96 38 35 97 36 27 98 35 32 99 38 26 100 37 29 101 39 29 102 39 31 103 40 32 104 38 31 105 40 29 106 39 25 107 41 25 108 41 30 109 42 31 110 40 38 111 15 117 112 16 118 113 17 118 114 17 39 115 14 38 116 15 42 117 18 6 118 222 2 119 221 2 120 221 41 121 19 42 122 18 48 123 43 44 124 44 47 125 45 47 126 45 49 127 46 48 128 43 49 129 46 47 130 45 43 131 47 43 132 47 50 133 48 49 134 46 51 135 55 36 136 56 38 137 57 51 138 55 38 139 57 39 140 58 51 141 55 39 142 58 40 143 59 40 144 59 46 145 60 52 146 61 52 147 61 51 148 55 40 149 59 46 150 60 45 151 62 53 152 63 53 153 63 52 154 61 46 155 60 45 156 62 44 157 44 48 158 43 48 159 43 53 160 63 45 161 62 56 162 20 11 163 207 16 164 212 16 165 212 57 166 21 56 167 20 57 168 21 16 169 212 5 170 211 5 171 211 58 172 22 57 173 21 63 174 24 116 175 49 122 176 50 122 177 50 62 178 23 63 179 24 69 180 67 68 181 68 61 182 69 61 183 69 67 184 70 69 185 67 65 186 71 70 187 72 69 188 67 69 189 67 67 190 70 65 191 71 64 192 73 71 193 74 70 194 72 70 195 72 65 196 71 64 197 73 66 198 75 72 199 76 71 200 74 71 201 74 64 202 73 66 203 75 59 204 77 73 205 78 72 206 76 72 207 76 66 208 75 59 209 77 313 210 52 119 211 53 78 212 54 78 213 54 77 214 51 313 215 52 119 216 53 315 217 79 76 218 80 76 219 80 78 220 54 119 221 53 81 222 81 80 223 82 15 224 219 15 225 219 10 226 218 81 227 81 3 228 220 15 229 219 80 230 82 80 231 82 83 232 83 3 233 220 85 234 90 88 235 91 89 236 92 89 237 92 87 238 93 85 239 90 90 240 94 88 241 91 85 242 90 85 243 90 84 244 95 90 245 94 86 246 96 91 247 97 90 248 94 90 249 94 84 250 95 86 251 96 92 252 98 91 253 97 86 254 96 86 255 96 79 256 99 92 257 98 87 258 93 89 259 92 93 260 100 93 261 100 82 262 101 87 263 93 495 264 11 24 265 10 25 266 85 25 267 85 568 268 84 495 269 11 23 270 103 19 271 104 30 272 42 24 273 102 23 274 103 30 275 42 24 276 102 30 277 42 25 278 41 30 279 29 19 280 30 18 281 64 18 282 64 33 283 28 30 284 29 44 285 87 104 286 88 105 287 89 105 288 89 47 289 86 44 290 87 41 291 106 37 292 107 50 293 48 42 294 105 41 295 106 50 296 48 42 297 105 50 298 48 43 299 47 36 300 65 51 301 66 50 302 111 50 303 111 37 304 112 36 305 65 67 306 114 123 307 115 573 308 116 573 309 116 97 310 117 67 311 114 63 312 109 62 313 110 60 314 126 54 315 108 63 316 109 60 317 126 68 318 68 54 319 108 60 320 126 68 321 68 60 322 126 61 323 69 56 324 127 57 325 128 58 326 129 56 327 127 58 328 129 55 329 130 56 330 127 55 331 130 73 332 78 56 333 127 73 334 78 59 335 77 68 336 113 73 337 139 55 338 140 55 339 140 54 340 141 68 341 113 116 342 177 63 343 178 54 344 188 54 345 188 952 346 1447 116 347 177 100 348 217 82 349 118 81 350 81 81 351 81 10 352 218 100 353 217 77 354 131 78 355 132 76 356 133 79 357 99 77 358 131 76 359 133 92 360 98 79 361 99 76 362 133 92 363 98 76 364 133 75 365 134 74 366 142 93 367 143 92 368 144 92 369 144 75 370 145 74 371 142 83 372 135 80 373 136 81 374 137 83 375 135 81 376 137 82 377 101 83 378 135 82 379 101 93 380 100 83 381 135 93 382 100 74 383 138 60 384 120 62 385 23 122 386 50 122 387 50 581 388 119 60 389 120 55 390 189 58 391 190 5 392 191 3 393 192 83 394 193 74 395 194 5 396 191 3 397 192 74 398 194 55 399 189 5 400 191 74 401 194 5 402 191 4 403 195 3 404 192 55 405 189 74 406 194 578 407 176 75 408 196 76 409 197 315 410 198 315 411 198 115 412 199 75 413 196 27 414 122 95 415 123 94 416 124 94 417 124 26 418 121 27 419 122 94 420 124 95 421 123 64 422 125 64 423 125 65 424 151 94 425 124 22 426 153 109 427 210 108 428 209 108 429 209 28 430 152 22 431 153 11 432 207 56 433 20 59 434 154 59 435 154 98 436 208 11 437 207 64 438 125 95 439 123 96 440 156 96 441 156 66 442 155 64 443 125 96 444 156 95 445 123 27 446 122 27 447 122 28 448 152 96 449 156 26 450 121 94 451 124 97 452 117 97 453 117 29 454 157 26 455 121 97 456 117 94 457 124 65 458 151 65 459 151 67 460 114 97 461 117 61 462 158 586 463 159 123 464 115 123 465 115 67 466 114 61 467 158 29 468 157 587 469 160 568 470 84 568 471 84 25 472 85 29 473 157 66 474 155 101 475 161 98 476 208 98 477 208 59 478 154 66 479 155 101 480 161 102 481 162 99 482 2 99 483 2 98 484 208 101 485 161 102 486 162 103 487 223 100 488 217 100 489 217 99 490 2 102 491 162 103 492 223 87 493 163 82 494 118 82 495 118 100 496 217 103 497 223 66 498 155 96 499 156 9 500 164 9 501 164 101 502 161 66 503 155 9 504 164 13 505 179 102 506 162 102 507 162 101 508 161 9 509 164 13 510 179 7 511 224 103 512 223 103 513 223 102 514 162 13 515 179 104 516 88 85 517 180 87 518 163 87 519 163 105 520 89 104 521 88 44 522 87 45 523 181 112 524 182 112 525 182 104 526 88 44 527 87 112 528 182 84 529 183 85 530 180 85 531 180 104 532 88 112 533 182 7 534 224 105 535 89 87 536 163 87 537 163 103 538 223 7 539 224 106 540 216 111 541 215 43 542 184 43 543 184 47 544 86 106 545 216 105 546 89 7 547 224 106 548 216 106 549 216 47 550 86 105 551 89 7 552 224 13 553 179 107 554 0 107 555 0 106 556 216 7 557 224 107 558 0 13 559 179 9 560 164 9 561 164 108 562 209 107 563 0 28 564 152 108 565 209 9 566 164 9 567 164 96 568 156 28 569 152 22 570 153 21 571 8 8 572 213 8 573 213 109 574 210 22 575 153 109 576 210 8 577 213 12 578 7 12 579 7 110 580 1 109 581 210 12 582 7 6 583 222 111 584 215 111 585 215 110 586 1 12 587 7 6 588 222 42 589 18 43 590 184 43 591 184 111 592 215 6 593 222 120 594 186 354 595 187 113 596 200 113 597 200 46 598 185 120 599 186 313 600 52 77 601 51 79 602 202 79 603 202 121 604 201 313 605 52 84 606 183 112 607 182 113 608 200 113 609 200 86 610 203 84 611 183 113 612 200 112 613 182 45 614 181 45 615 181 46 616 185 113 617 200 40 618 204 114 619 205 120 620 186 120 621 186 46 622 185 40 623 204 40 624 204 39 625 14 118 626 17 118 627 17 114 628 205 40 629 204 86 630 203 356 631 206 121 632 201 121 633 201 79 634 202 86 635 203 86 636 203 113 637 200 354 638 187 354 639 187 356 640 206 86 641 203 60 642 120 581 643 119 586 644 159 586 645 159 61 646 158 60 647 120 29 648 157 97 649 117 573 650 116 573 651 116 587 652 160 29 653 157 74 654 194 75 655 196 578 656 176 578 657 176 54 658 188 55 659 189 75 660 196 115 661 199 578 662 176 69 663 146 72 664 147 73 665 139 73 666 139 68 667 113 69 668 146 70 669 148 71 670 149 72 671 147 72 672 147 69 673 146 70 674 148 35 675 165 32 676 166 31 677 167 31 678 167 34 679 150 35 680 165 34 681 150 31 682 167 30 683 29 30 684 29 33 685 28 34 686 150 52 687 168 49 688 169 50 689 111 50 690 111 51 691 66 52 692 168 53 693 170 48 694 171 49 695 169 49 696 169 52 697 168 53 698 170 89 699 172 91 700 173 92 701 144 92 702 144 93 703 143 89 704 172 88 705 174 90 706 175 91 707 173 91 708 173 89 709 172 88 710 174 126 711 229 127 712 230 944 713 228 944 714 228 125 715 226 126 716 229 124 717 225 943 718 227 127 719 230 127 720 230 126 721 229 124 722 225 131 723 243 134 724 246 133 725 245 133 726 245 132 727 244 131 728 243 190 729 248 187 730 247 136 731 250 136 732 250 135 733 249 190 734 248 137 735 251 140 736 254 139 737 253 139 738 253 138 739 252 137 740 251 141 741 255 144 742 258 143 743 257 143 744 257 142 745 256 141 746 255 132 747 244 141 748 255 142 749 256 142 750 256 131 751 243 132 752 244 199 753 241 137 754 251 138 755 252 138 756 252 178 757 259 199 758 241 139 759 253 140 760 254 133 761 245 133 762 245 134 763 246 139 764 253 144 765 258 135 766 249 136 767 250 136 768 250 143 769 257 144 770 258 147 771 262 146 772 261 145 773 260 145 774 260 148 775 263 147 776 262 150 777 265 149 778 264 152 779 267 152 780 267 151 781 266 150 782 265 129 783 238 128 784 236 153 785 268 153 786 268 154 787 269 129 788 238 156 789 271 155 790 270 210 791 237 210 792 237 179 793 272 156 794 271 159 795 275 158 796 274 157 797 273 157 798 273 160 799 276 159 800 275 163 801 279 162 802 278 161 803 277 161 804 277 164 805 280 163 806 279 154 807 269 153 808 268 165 809 281 165 810 281 166 811 282 154 812 269 168 813 234 167 814 233 170 815 235 170 816 235 169 817 285 168 818 234 170 819 286 167 820 283 171 821 287 171 822 287 172 823 288 170 824 286 148 825 263 145 826 260 173 827 289 173 828 289 174 829 290 148 830 263 172 831 288 171 832 287 149 833 264 149 834 264 150 835 265 172 836 288 130 837 240 180 838 291 162 839 278 162 840 278 163 841 279 130 842 240 160 843 276 157 844 273 231 845 292 231 846 292 181 847 239 160 848 276 151 849 266 152 850 267 158 851 274 158 852 274 159 853 275 151 854 266 164 855 280 161 856 277 146 857 261 146 858 261 147 859 262 164 860 280 176 861 294 175 862 293 155 863 270 155 864 270 156 865 271 176 866 294 174 867 290 173 868 289 175 869 293 175 870 293 176 871 294 174 872 290 132 873 244 133 874 245 152 875 267 152 876 267 149 877 264 132 878 244 134 879 246 131 880 243 145 881 260 145 882 260 146 883 261 134 884 246 182 885 242 190 886 248 135 887 249 135 888 249 177 889 295 182 890 242 155 891 270 136 892 250 187 893 247 187 894 247 210 895 237 155 896 270 138 897 252 139 898 253 161 899 277 161 900 277 162 901 278 138 902 252 140 903 254 137 904 251 157 905 273 157 906 273 158 907 274 140 908 254 142 909 256 143 910 257 175 911 293 175 912 293 173 913 289 142 914 256 131 915 243 142 916 256 173 917 289 173 918 289 145 919 260 131 920 243 141 921 255 132 922 244 149 923 264 149 924 264 171 925 287 141 926 255 178 927 259 138 928 252 162 929 278 162 930 278 180 931 291 178 932 259 157 933 273 137 934 251 199 935 241 199 936 241 231 937 292 157 938 273 161 939 277 139 940 253 134 941 246 134 942 246 146 943 261 161 944 277 152 945 267 133 946 245 140 947 254 140 948 254 158 949 274 152 950 267 143 951 257 136 952 250 155 953 270 155 954 270 175 955 293 143 956 257 144 957 258 171 958 287 177 959 295 165 960 231 168 961 234 169 962 285 169 963 285 166 964 232 165 965 231 128 966 236 182 967 242 177 968 295 177 969 295 153 970 268 128 971 236 153 972 268 177 973 295 168 974 284 168 975 284 165 976 281 153 977 268 177 978 295 135 979 249 144 980 258 144 981 258 141 982 255 171 983 287 167 984 283 168 985 284 177 986 295 177 987 295 171 988 287 167 989 283 183 990 296 186 991 299 185 992 298 185 993 298 184 994 297 183 995 296 190 996 303 189 997 302 188 998 301 188 999 301 187 1000 300 190 1001 303 191 1002 304 194 1003 307 193 1004 306 193 1005 306 192 1006 305 191 1007 304 195 1008 308 198 1009 311 197 1010 310 197 1011 310 196 1012 309 195 1013 308 186 1014 299 183 1015 296 198 1016 311 198 1017 311 195 1018 308 186 1019 299 199 1020 312 178 1021 313 194 1022 307 194 1023 307 191 1024 304 199 1025 312 193 1026 306 184 1027 297 185 1028 298 185 1029 298 192 1030 305 193 1031 306 196 1032 309 197 1033 310 188 1034 301 188 1035 301 189 1036 302 196 1037 309 202 1038 316 201 1039 315 200 1040 314 200 1041 314 203 1042 317 202 1043 316 207 1044 321 206 1045 320 205 1046 319 205 1047 319 204 1048 318 207 1049 321 129 1050 324 209 1051 323 208 1052 322 208 1053 322 128 1054 325 129 1055 324 211 1056 328 179 1057 327 210 1058 326 210 1059 326 212 1060 329 211 1061 328 215 1062 332 214 1063 331 213 1064 330 213 1065 330 216 1066 333 215 1067 332 219 1068 336 218 1069 335 217 1070 334 217 1071 334 220 1072 337 219 1073 336 209 1074 323 222 1075 339 221 1076 338 221 1077 338 208 1078 322 209 1079 323 226 1080 343 225 1081 342 224 1082 341 224 1083 341 223 1084 340 226 1085 343 224 1086 346 228 1087 345 227 1088 344 227 1089 344 223 1090 347 224 1091 346 201 1092 315 230 1093 349 229 1094 348 229 1095 348 200 1096 314 201 1097 315 228 1098 345 207 1099 321 204 1100 318 204 1101 318 227 1102 344 228 1103 345 130 1104 350 219 1105 336 220 1106 337 220 1107 337 180 1108 351 130 1109 350 214 1110 331 181 1111 353 231 1112 352 231 1113 352 213 1114 330 214 1115 331 206 1116 320 215 1117 332 216 1118 333 216 1119 333 205 1120 319 206 1121 320 218 1122 335 202 1123 316 203 1124 317 203 1125 317 217 1126 334 218 1127 335 232 1128 354 211 1129 328 212 1130 329 212 1131 329 233 1132 355 232 1133 354 230 1134 349 232 1135 354 233 1136 355 233 1137 355 229 1138 348 230 1139 349 186 1140 299 204 1141 318 205 1142 319 205 1143 319 185 1144 298 186 1145 299 184 1146 297 203 1147 317 200 1148 314 200 1149 314 183 1150 296 184 1151 297 182 1152 357 234 1153 356 189 1154 302 189 1155 302 190 1156 303 182 1157 357 212 1158 329 210 1159 326 187 1160 300 187 1161 300 188 1162 301 212 1163 329 194 1164 307 220 1165 337 217 1166 334 217 1167 334 193 1168 306 194 1169 307 192 1170 305 216 1171 333 213 1172 330 213 1173 330 191 1174 304 192 1175 305 198 1176 311 229 1177 348 233 1178 355 233 1179 355 197 1180 310 198 1181 311 183 1182 296 200 1183 314 229 1184 348 229 1185 348 198 1186 311 183 1187 296 195 1188 308 227 1189 344 204 1190 318 204 1191 318 186 1192 299 195 1193 308 178 1194 313 180 1195 351 220 1196 337 220 1197 337 194 1198 307 178 1199 313 213 1200 330 231 1201 352 199 1202 312 199 1203 312 191 1204 304 213 1205 330 217 1206 334 203 1207 317 184 1208 297 184 1209 297 193 1210 306 217 1211 334 205 1212 319 216 1213 333 192 1214 305 192 1215 305 185 1216 298 205 1217 319 197 1218 310 233 1219 355 212 1220 329 212 1221 329 188 1222 301 197 1223 310 196 1224 309 234 1225 356 227 1226 344 221 1227 359 222 1228 358 225 1229 342 225 1230 342 226 1231 343 221 1232 359 128 1233 325 208 1234 322 234 1235 356 234 1236 356 182 1237 357 128 1238 325 208 1239 322 221 1240 338 226 1241 360 226 1242 360 234 1243 356 208 1244 322 234 1245 356 196 1246 309 189 1247 302 196 1248 309 227 1249 344 195 1250 308 223 1251 347 227 1252 344 234 1253 356 234 1254 356 226 1255 360 223 1256 347 236 1257 362 235 1258 361 238 1259 364 238 1260 364 237 1261 363 236 1262 362 240 1263 366 239 1264 365 242 1265 368 242 1266 368 241 1267 367 240 1268 366 238 1269 364 244 1270 370 243 1271 369 243 1272 369 237 1273 363 238 1274 364 241 1275 367 242 1276 368 246 1277 372 246 1278 372 245 1279 371 241 1280 367 249 1281 375 248 1282 374 247 1283 373 247 1284 373 250 1285 376 249 1286 375 251 1287 377 249 1288 375 250 1289 376 250 1290 376 252 1291 378 251 1292 377 250 1293 376 247 1294 373 246 1295 372 246 1296 372 242 1297 368 250 1298 376 252 1299 378 250 1300 376 242 1301 368 242 1302 368 239 1303 365 252 1304 378 253 1305 379 256 1306 382 255 1307 381 255 1308 381 254 1309 380 253 1310 379 255 1311 381 256 1312 382 258 1313 384 258 1314 384 257 1315 383 255 1316 381 254 1317 380 260 1318 386 259 1319 385 259 1320 385 253 1321 379 254 1322 380 262 1323 388 261 1324 387 263 1325 390 263 1326 390 740 1327 389 262 1328 388 264 1329 391 266 1330 395 259 1331 394 264 1332 391 259 1333 394 260 1334 393 264 1335 391 260 1336 393 265 1337 392 266 1338 395 264 1339 391 268 1340 397 268 1341 397 267 1342 396 266 1343 395 267 1344 396 268 1345 397 270 1346 399 270 1347 399 269 1348 398 267 1349 396 269 1350 398 270 1351 399 272 1352 401 272 1353 401 271 1354 400 269 1355 398 272 1356 401 274 1357 403 273 1358 402 273 1359 402 271 1360 400 272 1361 401 274 1362 403 276 1363 405 275 1364 404 275 1365 404 273 1366 402 274 1367 403 278 1368 407 277 1369 406 118 1370 409 118 1371 409 117 1372 408 278 1373 407 279 1374 410 280 1375 411 257 1376 383 257 1377 383 258 1378 384 279 1379 410 281 1380 412 284 1381 415 283 1382 414 283 1383 414 282 1384 413 281 1385 412 284 1386 415 286 1387 417 285 1388 416 285 1389 416 283 1390 414 284 1391 415 287 1392 418 289 1393 422 277 1394 421 287 1395 418 277 1396 421 278 1397 420 287 1398 418 278 1399 420 288 1400 419 289 1401 422 287 1402 418 291 1403 424 291 1404 424 290 1405 423 289 1406 422 290 1407 423 291 1408 424 293 1409 426 293 1410 426 292 1411 425 290 1412 423 292 1413 425 293 1414 426 281 1415 412 281 1416 412 282 1417 413 292 1418 425 294 1419 427 295 1420 428 252 1421 378 252 1422 378 239 1423 365 294 1424 427 295 1425 428 296 1426 429 251 1427 377 251 1428 377 252 1429 378 295 1430 428 298 1431 431 297 1432 430 775 1433 433 775 1434 433 299 1435 432 298 1436 431 300 1437 434 303 1438 437 302 1439 436 302 1440 436 301 1441 435 300 1442 434 304 1443 438 303 1444 437 300 1445 434 300 1446 434 305 1447 439 304 1448 438 306 1449 440 304 1450 438 305 1451 439 305 1452 439 307 1453 441 306 1454 440 308 1455 442 306 1456 440 307 1457 441 307 1458 441 309 1459 443 308 1460 442 310 1461 444 308 1462 442 309 1463 443 309 1464 443 311 1465 445 310 1466 444 313 1467 447 312 1468 446 314 1469 449 314 1470 449 119 1471 448 313 1472 447 119 1473 448 314 1474 449 316 1475 451 316 1476 451 315 1477 450 119 1478 448 317 1479 452 246 1480 372 247 1481 373 247 1482 373 318 1483 453 317 1484 452 248 1485 374 319 1486 454 318 1487 453 318 1488 453 247 1489 373 248 1490 374 320 1491 455 323 1492 458 322 1493 457 322 1494 457 321 1495 456 320 1496 455 324 1497 459 325 1498 460 320 1499 455 320 1500 455 321 1501 456 324 1502 459 326 1503 461 325 1504 460 324 1505 459 324 1506 459 327 1507 462 326 1508 461 328 1509 463 329 1510 464 326 1511 461 326 1512 461 327 1513 462 328 1514 463 323 1515 458 331 1516 466 330 1517 465 330 1518 465 322 1519 457 323 1520 458 262 1521 388 332 1522 467 275 1523 468 275 1524 468 261 1525 387 262 1526 388 261 1527 469 275 1528 404 276 1529 405 276 1530 405 333 1531 471 263 1532 470 261 1533 469 276 1534 405 263 1535 470 276 1536 473 264 1537 472 265 1538 475 265 1539 475 333 1540 474 276 1541 473 282 1542 477 283 1543 476 335 1544 479 335 1545 479 334 1546 478 282 1547 477 279 1548 480 285 1549 416 286 1550 417 286 1551 417 336 1552 482 280 1553 481 279 1554 480 286 1555 417 280 1556 481 288 1557 483 336 1558 486 286 1559 485 286 1560 485 287 1561 484 288 1562 483 303 1563 487 337 1564 490 812 1565 489 812 1566 489 813 1567 488 303 1568 487 301 1569 435 302 1570 436 339 1571 494 339 1572 494 297 1573 493 298 1574 492 339 1575 494 298 1576 492 338 1577 491 301 1578 435 339 1579 494 338 1580 491 294 1581 495 310 1582 444 311 1583 445 294 1584 495 311 1585 445 340 1586 498 294 1587 495 340 1588 498 296 1589 497 294 1590 495 296 1591 497 295 1592 496 301 1593 499 338 1594 502 340 1595 501 340 1596 501 311 1597 500 301 1598 499 578 1599 503 338 1600 506 951 1601 1444 245 1602 371 246 1603 372 317 1604 452 317 1605 452 331 1606 507 245 1607 371 328 1608 463 341 1609 511 316 1610 510 316 1611 510 314 1612 509 312 1613 508 316 1614 510 312 1615 508 329 1616 464 328 1617 463 316 1618 510 329 1619 464 342 1620 512 341 1621 515 328 1622 514 328 1623 514 330 1624 513 342 1625 512 319 1626 516 342 1627 519 330 1628 465 319 1629 516 330 1630 465 331 1631 466 319 1632 516 331 1633 466 317 1634 518 319 1635 516 317 1636 518 318 1637 517 339 1638 521 343 1639 520 775 1640 433 775 1641 433 297 1642 430 339 1643 521 342 1644 527 319 1645 526 248 1646 525 342 1647 527 248 1648 525 251 1649 524 340 1650 522 342 1651 527 251 1652 524 340 1653 522 251 1654 524 296 1655 523 251 1656 524 248 1657 525 249 1658 528 340 1659 522 578 1660 503 342 1661 527 341 1662 529 115 1663 532 315 1664 531 315 1665 531 316 1666 530 341 1667 529 269 1668 534 271 1669 533 345 1670 536 345 1671 536 344 1672 535 269 1673 534 345 1674 536 304 1675 538 306 1676 537 306 1677 537 344 1678 535 345 1679 536 266 1680 540 267 1681 539 243 1682 369 243 1683 369 244 1684 370 266 1685 540 239 1686 365 240 1687 366 310 1688 541 310 1689 541 294 1690 427 239 1691 365 306 1692 537 308 1693 542 346 1694 543 346 1695 543 344 1696 535 306 1697 537 346 1698 543 267 1699 539 269 1700 534 269 1701 534 344 1702 535 346 1703 543 271 1704 533 273 1705 544 337 1706 490 337 1707 490 345 1708 536 271 1709 533 337 1710 490 303 1711 487 304 1712 538 304 1713 538 345 1714 536 337 1715 490 302 1716 545 303 1717 487 813 1718 488 813 1719 488 822 1720 546 302 1721 545 273 1722 544 275 1723 468 332 1724 467 332 1725 467 823 1726 547 273 1727 544 308 1728 542 310 1729 541 240 1730 366 240 1731 366 347 1732 548 308 1733 542 347 1734 548 240 1735 366 241 1736 367 241 1737 367 348 1738 549 347 1739 548 348 1740 549 241 1741 367 245 1742 371 245 1743 371 349 1744 550 348 1745 549 349 1746 550 245 1747 371 331 1748 507 331 1749 507 323 1750 551 349 1751 550 308 1752 542 347 1753 548 350 1754 552 350 1755 552 346 1756 543 308 1757 542 350 1758 552 347 1759 548 348 1760 549 348 1761 549 351 1762 553 350 1763 552 351 1764 553 348 1765 549 349 1766 550 349 1767 550 352 1768 554 351 1769 553 334 1770 478 335 1771 479 323 1772 551 323 1773 551 320 1774 555 334 1775 478 282 1776 477 334 1777 478 353 1778 557 353 1779 557 292 1780 556 282 1781 477 353 1782 557 334 1783 478 320 1784 555 320 1785 555 325 1786 558 353 1787 557 352 1788 554 349 1789 550 323 1790 551 323 1791 551 335 1792 479 352 1793 554 236 1794 362 283 1795 476 285 1796 559 285 1797 559 235 1798 361 236 1799 362 335 1800 479 283 1801 476 236 1802 362 236 1803 362 352 1804 554 335 1805 479 352 1806 554 236 1807 362 237 1808 363 237 1809 363 351 1810 553 352 1811 554 237 1812 363 243 1813 369 350 1814 552 350 1815 552 351 1816 553 237 1817 363 267 1818 539 346 1819 543 350 1820 552 350 1821 552 243 1822 369 267 1823 539 266 1824 540 244 1825 370 253 1826 379 253 1827 379 259 1828 385 266 1829 540 244 1830 370 238 1831 364 256 1832 382 256 1833 382 253 1834 379 244 1835 370 256 1836 382 238 1837 364 235 1838 361 235 1839 361 258 1840 384 256 1841 382 258 1842 384 235 1843 361 285 1844 559 285 1845 559 279 1846 410 258 1847 384 120 1848 561 290 1849 560 355 1850 563 355 1851 563 354 1852 562 120 1853 561 313 1854 447 121 1855 564 329 1856 565 329 1857 565 312 1858 446 313 1859 447 325 1860 558 326 1861 566 355 1862 563 355 1863 563 353 1864 557 325 1865 558 355 1866 563 290 1867 560 292 1868 556 292 1869 556 353 1870 557 355 1871 563 289 1872 567 290 1873 560 120 1874 561 120 1875 561 114 1876 568 289 1877 567 289 1878 567 114 1879 568 118 1880 409 118 1881 409 277 1882 406 289 1883 567 326 1884 566 329 1885 565 121 1886 564 121 1887 564 356 1888 569 326 1889 566 326 1890 566 356 1891 569 354 1892 562 354 1893 562 355 1894 563 326 1895 566 339 1896 521 302 1897 545 822 1898 546 822 1899 546 343 1900 520 339 1901 521 273 1902 544 823 1903 547 812 1904 489 812 1905 489 337 1906 490 273 1907 544 342 1908 527 578 1909 503 341 1910 529 578 1911 503 340 1912 522 338 1913 506 341 1914 529 578 1915 503 115 1916 532 300 1917 570 301 1918 499 311 1919 500 311 1920 500 309 1921 571 300 1922 570 305 1923 572 300 1924 570 309 1925 571 309 1926 571 307 1927 573 305 1928 572 270 1929 575 268 1930 574 274 1931 577 274 1932 577 272 1933 576 270 1934 575 268 1935 574 264 1936 472 276 1937 473 276 1938 473 274 1939 577 268 1940 574 291 1941 578 287 1942 484 286 1943 485 286 1944 485 284 1945 579 291 1946 578 293 1947 580 291 1948 578 284 1949 579 284 1950 579 281 1951 581 293 1952 580 322 1953 582 330 1954 513 328 1955 514 328 1956 514 327 1957 583 322 1958 582 321 1959 584 322 1960 582 327 1961 583 327 1962 583 324 1963 585 321 1964 584 358 1965 587 357 1966 586 945 1967 589 945 1968 589 359 1969 588 358 1970 587 361 1971 590 358 1972 587 359 1973 588 359 1974 588 946 1975 591 361 1976 590 363 1977 592 366 1978 595 365 1979 594 365 1980 594 364 1981 593 363 1982 592 370 1983 599 369 1984 598 368 1985 597 368 1986 597 367 1987 596 370 1988 599 371 1989 600 374 1990 603 373 1991 602 373 1992 602 372 1993 601 371 1994 600 375 1995 604 378 1996 607 377 1997 606 377 1998 606 376 1999 605 375 2000 604 366 2001 595 363 2002 592 378 2003 607 378 2004 607 375 2005 604 366 2006 595 379 2007 608 380 2008 609 374 2009 603 374 2010 603 371 2011 600 379 2012 608 373 2013 602 364 2014 593 365 2015 594 365 2016 594 372 2017 601 373 2018 602 376 2019 605 377 2020 606 368 2021 597 368 2022 597 369 2023 598 376 2024 605 383 2025 612 382 2026 611 381 2027 610 381 2028 610 384 2029 613 383 2030 612 388 2031 617 387 2032 616 386 2033 615 386 2034 615 385 2035 614 388 2036 617 391 2037 620 390 2038 619 389 2039 618 389 2040 618 392 2041 621 391 2042 620 395 2043 624 394 2044 623 393 2045 622 393 2046 622 396 2047 625 395 2048 624 399 2049 628 398 2050 627 397 2051 626 397 2052 626 400 2053 629 399 2054 628 403 2055 632 402 2056 631 401 2057 630 401 2058 630 404 2059 633 403 2060 632 390 2061 619 406 2062 635 405 2063 634 405 2064 634 389 2065 618 390 2066 619 410 2067 639 409 2068 638 408 2069 637 408 2070 637 407 2071 636 410 2072 639 408 2073 642 412 2074 641 411 2075 640 411 2076 640 407 2077 643 408 2078 642 382 2079 611 414 2080 645 413 2081 644 413 2082 644 381 2083 610 382 2084 611 412 2085 641 388 2086 617 385 2087 614 385 2088 614 411 2089 640 412 2090 641 415 2091 646 403 2092 632 404 2093 633 404 2094 633 416 2095 647 415 2096 646 398 2097 627 418 2098 649 417 2099 648 417 2100 648 397 2101 626 398 2102 627 387 2103 616 399 2104 628 400 2105 629 400 2106 629 386 2107 615 387 2108 616 402 2109 631 383 2110 612 384 2111 613 384 2112 613 401 2113 630 402 2114 631 419 2115 650 395 2116 624 396 2117 625 396 2118 625 420 2119 651 419 2120 650 414 2121 645 419 2122 650 420 2123 651 420 2124 651 413 2125 644 414 2126 645 366 2127 595 385 2128 614 386 2129 615 386 2130 615 365 2131 594 366 2132 595 364 2133 593 384 2134 613 381 2135 610 381 2136 610 363 2137 592 364 2138 593 422 2139 653 421 2140 652 369 2141 598 369 2142 598 370 2143 599 422 2144 653 396 2145 625 393 2146 622 367 2147 596 367 2148 596 368 2149 597 396 2150 625 374 2151 603 404 2152 633 401 2153 630 401 2154 630 373 2155 602 374 2156 603 372 2157 601 400 2158 629 397 2159 626 397 2160 626 371 2161 600 372 2162 601 378 2163 607 413 2164 644 420 2165 651 420 2166 651 377 2167 606 378 2168 607 363 2169 592 381 2170 610 413 2171 644 413 2172 644 378 2173 607 363 2174 592 375 2175 604 411 2176 640 385 2177 614 385 2178 614 366 2179 595 375 2180 604 380 2181 609 416 2182 647 404 2183 633 404 2184 633 374 2185 603 380 2186 609 397 2187 626 417 2188 648 379 2189 608 379 2190 608 371 2191 600 397 2192 626 401 2193 630 384 2194 613 364 2195 593 364 2196 593 373 2197 602 401 2198 630 386 2199 615 400 2200 629 372 2201 601 372 2202 601 365 2203 594 386 2204 615 377 2205 606 420 2206 651 396 2207 625 396 2208 625 368 2209 597 377 2210 606 376 2211 605 421 2212 652 411 2213 640 405 2214 655 406 2215 654 409 2216 638 409 2217 638 410 2218 639 405 2219 655 392 2220 621 389 2221 618 421 2222 652 421 2223 652 422 2224 653 392 2225 621 389 2226 618 405 2227 634 410 2228 656 410 2229 656 421 2230 652 389 2231 618 421 2232 652 376 2233 605 369 2234 598 376 2235 605 411 2236 640 375 2237 604 407 2238 643 411 2239 640 421 2240 652 421 2241 652 410 2242 656 407 2243 643 423 2244 657 426 2245 660 425 2246 659 425 2247 659 424 2248 658 423 2249 657 370 2250 662 367 2251 661 428 2252 664 428 2253 664 427 2254 663 370 2255 662 429 2256 665 432 2257 668 431 2258 667 431 2259 667 430 2260 666 429 2261 665 433 2262 669 436 2263 672 435 2264 671 435 2265 671 434 2266 670 433 2267 669 424 2268 658 433 2269 669 434 2270 670 434 2271 670 423 2272 657 424 2273 658 379 2274 673 429 2275 665 430 2276 666 430 2277 666 380 2278 674 379 2279 673 431 2280 667 432 2281 668 425 2282 659 425 2283 659 426 2284 660 431 2285 667 436 2286 672 427 2287 663 428 2288 664 428 2289 664 435 2290 671 436 2291 672 439 2292 677 438 2293 676 437 2294 675 437 2295 675 440 2296 678 439 2297 677 442 2298 680 441 2299 679 444 2300 682 444 2301 682 443 2302 681 442 2303 680 391 2304 685 392 2305 684 445 2306 683 445 2307 683 446 2308 686 391 2309 685 448 2310 689 447 2311 688 393 2312 687 393 2313 687 394 2314 690 448 2315 689 451 2316 693 450 2317 692 449 2318 691 449 2319 691 452 2320 694 451 2321 693 455 2322 697 454 2323 696 453 2324 695 453 2325 695 456 2326 698 455 2327 697 446 2328 686 445 2329 683 457 2330 699 457 2331 699 362 2332 700 446 2333 686 459 2334 702 458 2335 701 360 2336 704 360 2337 704 460 2338 703 459 2339 702 360 2340 707 458 2341 706 461 2342 705 461 2343 705 462 2344 708 360 2345 707 440 2346 678 437 2347 675 463 2348 709 463 2349 709 464 2350 710 440 2351 678 462 2352 708 461 2353 705 441 2354 679 441 2355 679 442 2356 680 462 2357 708 415 2358 712 416 2359 711 454 2360 696 454 2361 696 455 2362 697 415 2363 712 452 2364 694 449 2365 691 417 2366 713 417 2367 713 418 2368 714 452 2369 694 443 2370 681 444 2371 682 450 2372 692 450 2373 692 451 2374 693 443 2375 681 456 2376 698 453 2377 695 438 2378 676 438 2379 676 439 2380 677 456 2381 698 466 2382 716 465 2383 715 447 2384 688 447 2385 688 448 2386 689 466 2387 716 464 2388 710 463 2389 709 465 2390 715 465 2391 715 466 2392 716 464 2393 710 424 2394 658 425 2395 659 444 2396 682 444 2397 682 441 2398 679 424 2399 658 426 2400 660 423 2401 657 437 2402 675 437 2403 675 438 2404 676 426 2405 660 422 2406 717 370 2407 662 427 2408 663 427 2409 663 467 2410 718 422 2411 717 447 2412 688 428 2413 664 367 2414 661 367 2415 661 393 2416 687 447 2417 688 430 2418 666 431 2419 667 453 2420 695 453 2421 695 454 2422 696 430 2423 666 432 2424 668 429 2425 665 449 2426 691 449 2427 691 450 2428 692 432 2429 668 434 2430 670 435 2431 671 465 2432 715 465 2433 715 463 2434 709 434 2435 670 423 2436 657 434 2437 670 463 2438 709 463 2439 709 437 2440 675 423 2441 657 433 2442 669 424 2443 658 441 2444 679 441 2445 679 461 2446 705 433 2447 669 380 2448 674 430 2449 666 454 2450 696 454 2451 696 416 2452 711 380 2453 674 449 2454 691 429 2455 665 379 2456 673 379 2457 673 417 2458 713 449 2459 691 453 2460 695 431 2461 667 426 2462 660 426 2463 660 438 2464 676 453 2465 695 444 2466 682 425 2467 659 432 2468 668 432 2469 668 450 2470 692 444 2471 682 435 2472 671 428 2473 664 447 2474 688 447 2475 688 465 2476 715 435 2477 671 436 2478 672 461 2479 705 467 2480 718 457 2481 719 459 2482 702 460 2483 703 460 2484 703 362 2485 720 457 2486 719 392 2487 684 422 2488 717 467 2489 718 467 2490 718 445 2491 683 392 2492 684 445 2493 683 467 2494 718 459 2495 721 459 2496 721 457 2497 699 445 2498 683 467 2499 718 427 2500 663 436 2501 672 436 2502 672 433 2503 669 461 2504 705 458 2505 706 459 2506 721 467 2507 718 467 2508 718 461 2509 705 458 2510 706 469 2511 723 468 2512 722 471 2513 725 471 2514 725 470 2515 724 469 2516 723 473 2517 727 472 2518 726 475 2519 729 475 2520 729 474 2521 728 473 2522 727 471 2523 725 477 2524 731 476 2525 730 476 2526 730 470 2527 724 471 2528 725 474 2529 728 475 2530 729 479 2531 733 479 2532 733 478 2533 732 474 2534 728 482 2535 736 481 2536 735 480 2537 734 480 2538 734 483 2539 737 482 2540 736 484 2541 738 482 2542 736 483 2543 737 483 2544 737 485 2545 739 484 2546 738 483 2547 737 480 2548 734 479 2549 733 479 2550 733 475 2551 729 483 2552 737 485 2553 739 483 2554 737 475 2555 729 475 2556 729 472 2557 726 485 2558 739 486 2559 740 489 2560 743 488 2561 742 488 2562 742 487 2563 741 486 2564 740 488 2565 742 489 2566 743 491 2567 745 491 2568 745 490 2569 744 488 2570 742 487 2571 741 493 2572 747 492 2573 746 492 2574 746 486 2575 740 487 2576 741 495 2577 749 494 2578 748 497 2579 751 497 2580 751 496 2581 750 495 2582 749 498 2583 752 500 2584 756 492 2585 755 498 2586 752 492 2587 755 493 2588 754 498 2589 752 493 2590 754 499 2591 753 500 2592 756 498 2593 752 502 2594 758 502 2595 758 501 2596 757 500 2597 756 501 2598 757 502 2599 758 504 2600 760 504 2601 760 503 2602 759 501 2603 757 503 2604 759 504 2605 760 506 2606 762 506 2607 762 505 2608 761 503 2609 759 506 2610 762 508 2611 764 507 2612 763 507 2613 763 505 2614 761 506 2615 762 508 2616 764 510 2617 766 509 2618 765 509 2619 765 507 2620 763 508 2621 764 512 2622 768 511 2623 767 514 2624 770 514 2625 770 513 2626 769 512 2627 768 515 2628 771 516 2629 772 490 2630 744 490 2631 744 491 2632 745 515 2633 771 517 2634 773 520 2635 776 519 2636 775 519 2637 775 518 2638 774 517 2639 773 520 2640 776 522 2641 778 521 2642 777 521 2643 777 519 2644 775 520 2645 776 523 2646 779 525 2647 783 511 2648 782 523 2649 779 511 2650 782 512 2651 781 523 2652 779 512 2653 781 524 2654 780 525 2655 783 523 2656 779 527 2657 785 527 2658 785 526 2659 784 525 2660 783 526 2661 784 527 2662 785 529 2663 787 529 2664 787 528 2665 786 526 2666 784 528 2667 786 529 2668 787 517 2669 773 517 2670 773 518 2671 774 528 2672 786 530 2673 788 531 2674 789 485 2675 739 485 2676 739 472 2677 726 530 2678 788 531 2679 789 532 2680 790 484 2681 738 484 2682 738 485 2683 739 531 2684 789 534 2685 792 533 2686 791 122 2687 794 122 2688 794 116 2689 793 534 2690 792 535 2691 795 538 2692 798 537 2693 797 537 2694 797 536 2695 796 535 2696 795 539 2697 799 538 2698 798 535 2699 795 535 2700 795 540 2701 800 539 2702 799 541 2703 801 539 2704 799 540 2705 800 540 2706 800 542 2707 802 541 2708 801 543 2709 803 541 2710 801 542 2711 802 542 2712 802 544 2713 804 543 2714 803 545 2715 805 543 2716 803 544 2717 804 544 2718 804 546 2719 806 545 2720 805 548 2721 808 547 2722 807 550 2723 810 550 2724 810 549 2725 809 548 2726 808 549 2727 809 550 2728 810 552 2729 812 552 2730 812 551 2731 811 549 2732 809 553 2733 813 479 2734 733 480 2735 734 480 2736 734 554 2737 814 553 2738 813 481 2739 735 555 2740 815 554 2741 814 554 2742 814 480 2743 734 481 2744 735 556 2745 816 559 2746 819 558 2747 818 558 2748 818 557 2749 817 556 2750 816 560 2751 820 561 2752 821 556 2753 816 556 2754 816 557 2755 817 560 2756 820 562 2757 822 561 2758 821 560 2759 820 560 2760 820 563 2761 823 562 2762 822 564 2763 824 565 2764 825 562 2765 822 562 2766 822 563 2767 823 564 2768 824 559 2769 819 567 2770 827 566 2771 826 566 2772 826 558 2773 818 559 2774 819 495 2775 749 568 2776 828 509 2777 829 509 2778 829 494 2779 748 495 2780 749 494 2781 830 509 2782 765 510 2783 766 510 2784 766 569 2785 832 497 2786 831 494 2787 830 510 2788 766 497 2789 831 510 2790 834 498 2791 833 499 2792 836 499 2793 836 569 2794 835 510 2795 834 518 2796 838 519 2797 837 571 2798 840 571 2799 840 570 2800 839 518 2801 838 515 2802 841 521 2803 777 522 2804 778 522 2805 778 572 2806 843 516 2807 842 515 2808 841 522 2809 778 516 2810 842 524 2811 844 572 2812 847 522 2813 846 522 2814 846 523 2815 845 524 2816 844 538 2817 848 574 2818 851 573 2819 850 573 2820 850 123 2821 849 538 2822 848 536 2823 796 537 2824 797 576 2825 855 576 2826 855 533 2827 854 534 2828 853 576 2829 855 534 2830 853 575 2831 852 536 2832 796 576 2833 855 575 2834 852 530 2835 856 545 2836 805 546 2837 806 530 2838 856 546 2839 806 577 2840 859 530 2841 856 577 2842 859 532 2843 858 530 2844 856 532 2845 858 531 2846 857 536 2847 860 575 2848 863 577 2849 862 577 2850 862 546 2851 861 536 2852 860 116 2853 865 952 2854 1446 575 2855 867 575 2856 867 534 2857 866 116 2858 865 478 2859 732 479 2860 733 553 2861 813 553 2862 813 567 2863 868 478 2864 732 564 2865 824 579 2866 872 552 2867 871 552 2868 871 550 2869 870 547 2870 869 552 2871 871 547 2872 869 565 2873 825 564 2874 824 552 2875 871 565 2876 825 580 2877 873 579 2878 876 564 2879 875 564 2880 875 566 2881 874 580 2882 873 555 2883 877 580 2884 880 566 2885 826 555 2886 877 566 2887 826 567 2888 827 555 2889 877 567 2890 827 553 2891 879 555 2892 877 553 2893 879 554 2894 878 576 2895 882 581 2896 881 122 2897 794 122 2898 794 533 2899 791 576 2900 882 580 2901 888 555 2902 887 481 2903 886 580 2904 888 481 2905 886 484 2906 885 577 2907 883 580 2908 888 484 2909 885 577 2910 883 484 2911 885 532 2912 884 484 2913 885 481 2914 886 482 2915 889 577 2916 883 578 2917 864 580 2918 888 579 2919 890 582 2920 893 551 2921 892 551 2922 892 552 2923 891 579 2924 890 503 2925 895 505 2926 894 584 2927 897 584 2928 897 583 2929 896 503 2930 895 584 2931 897 539 2932 899 541 2933 898 541 2934 898 583 2935 896 584 2936 897 500 2937 901 501 2938 900 476 2939 730 476 2940 730 477 2941 731 500 2942 901 472 2943 726 473 2944 727 545 2945 902 545 2946 902 530 2947 788 472 2948 726 541 2949 898 543 2950 903 585 2951 904 585 2952 904 583 2953 896 541 2954 898 585 2955 904 501 2956 900 503 2957 895 503 2958 895 583 2959 896 585 2960 904 505 2961 894 507 2962 905 574 2963 851 574 2964 851 584 2965 897 505 2966 894 574 2967 851 538 2968 848 539 2969 899 539 2970 899 584 2971 897 574 2972 851 537 2973 906 538 2974 848 123 2975 849 123 2976 849 586 2977 907 537 2978 906 507 2979 905 509 2980 829 568 2981 828 568 2982 828 587 2983 908 507 2984 905 543 2985 903 545 2986 902 473 2987 727 473 2988 727 588 2989 909 543 2990 903 588 2991 909 473 2992 727 474 2993 728 474 2994 728 589 2995 910 588 2996 909 589 2997 910 474 2998 728 478 2999 732 478 3000 732 590 3001 911 589 3002 910 590 3003 911 478 3004 732 567 3005 868 567 3006 868 559 3007 912 590 3008 911 543 3009 903 588 3010 909 591 3011 913 591 3012 913 585 3013 904 543 3014 903 591 3015 913 588 3016 909 589 3017 910 589 3018 910 592 3019 914 591 3020 913 592 3021 914 589 3022 910 590 3023 911 590 3024 911 593 3025 915 592 3026 914 570 3027 839 571 3028 840 559 3029 912 559 3030 912 556 3031 916 570 3032 839 518 3033 838 570 3034 839 594 3035 918 594 3036 918 528 3037 917 518 3038 838 594 3039 918 570 3040 839 556 3041 916 556 3042 916 561 3043 919 594 3044 918 593 3045 915 590 3046 911 559 3047 912 559 3048 912 571 3049 840 593 3050 915 469 3051 723 519 3052 837 521 3053 920 521 3054 920 468 3055 722 469 3056 723 571 3057 840 519 3058 837 469 3059 723 469 3060 723 593 3061 915 571 3062 840 593 3063 915 469 3064 723 470 3065 724 470 3066 724 592 3067 914 593 3068 915 470 3069 724 476 3070 730 591 3071 913 591 3072 913 592 3073 914 470 3074 724 501 3075 900 585 3076 904 591 3077 913 591 3078 913 476 3079 730 501 3080 900 500 3081 901 477 3082 731 486 3083 740 486 3084 740 492 3085 746 500 3086 901 477 3087 731 471 3088 725 489 3089 743 489 3090 743 486 3091 740 477 3092 731 489 3093 743 471 3094 725 468 3095 722 468 3096 722 491 3097 745 489 3098 743 491 3099 745 468 3100 722 521 3101 920 521 3102 920 515 3103 771 491 3104 745 595 3105 922 526 3106 921 597 3107 924 597 3108 924 596 3109 923 595 3110 922 548 3111 808 598 3112 925 565 3113 926 565 3114 926 547 3115 807 548 3116 808 561 3117 919 562 3118 927 597 3119 924 597 3120 924 594 3121 918 561 3122 919 597 3123 924 526 3124 921 528 3125 917 528 3126 917 594 3127 918 597 3128 924 525 3129 928 526 3130 921 595 3131 922 595 3132 922 599 3133 929 525 3134 928 525 3135 928 599 3136 929 514 3137 770 514 3138 770 511 3139 767 525 3140 928 562 3141 927 565 3142 926 598 3143 925 598 3144 925 600 3145 930 562 3146 927 562 3147 927 600 3148 930 596 3149 923 596 3150 923 597 3151 924 562 3152 927 576 3153 882 537 3154 906 586 3155 907 586 3156 907 581 3157 881 576 3158 882 507 3159 905 587 3160 908 573 3161 850 573 3162 850 574 3163 851 507 3164 905 580 3165 888 578 3166 864 579 3167 890 578 3168 864 577 3169 883 575 3170 867 579 3171 890 578 3172 864 582 3173 893 535 3174 931 536 3175 860 546 3176 861 546 3177 861 544 3178 932 535 3179 931 540 3180 933 535 3181 931 544 3182 932 544 3183 932 542 3184 934 540 3185 933 504 3186 936 502 3187 935 508 3188 938 508 3189 938 506 3190 937 504 3191 936 502 3192 935 498 3193 833 510 3194 834 510 3195 834 508 3196 938 502 3197 935 527 3198 939 523 3199 845 522 3200 846 522 3201 846 520 3202 940 527 3203 939 529 3204 941 527 3205 939 520 3206 940 520 3207 940 517 3208 942 529 3209 941 558 3210 943 566 3211 874 564 3212 875 564 3213 875 563 3214 944 558 3215 943 557 3216 945 558 3217 943 563 3218 944 563 3219 944 560 3220 946 557 3221 945 602 3222 948 601 3223 947 947 3224 950 947 3225 950 603 3226 949 602 3227 948 605 3228 951 602 3229 948 603 3230 949 603 3231 949 948 3232 952 605 3233 951 607 3234 953 610 3235 956 609 3236 955 609 3237 955 608 3238 954 607 3239 953 614 3240 960 613 3241 959 612 3242 958 612 3243 958 611 3244 957 614 3245 960 615 3246 961 618 3247 964 617 3248 963 617 3249 963 616 3250 962 615 3251 961 619 3252 965 622 3253 968 621 3254 967 621 3255 967 620 3256 966 619 3257 965 610 3258 956 607 3259 953 622 3260 968 622 3261 968 619 3262 965 610 3263 956 623 3264 969 624 3265 970 618 3266 964 618 3267 964 615 3268 961 623 3269 969 617 3270 963 608 3271 954 609 3272 955 609 3273 955 616 3274 962 617 3275 963 620 3276 966 621 3277 967 612 3278 958 612 3279 958 613 3280 959 620 3281 966 627 3282 973 626 3283 972 625 3284 971 625 3285 971 628 3286 974 627 3287 973 632 3288 978 631 3289 977 630 3290 976 630 3291 976 629 3292 975 632 3293 978 635 3294 981 634 3295 980 633 3296 979 633 3297 979 636 3298 982 635 3299 981 639 3300 985 638 3301 984 637 3302 983 637 3303 983 640 3304 986 639 3305 985 643 3306 989 642 3307 988 641 3308 987 641 3309 987 644 3310 990 643 3311 989 647 3312 993 646 3313 992 645 3314 991 645 3315 991 648 3316 994 647 3317 993 634 3318 980 650 3319 996 649 3320 995 649 3321 995 633 3322 979 634 3323 980 654 3324 1000 653 3325 999 652 3326 998 652 3327 998 651 3328 997 654 3329 1000 652 3330 1003 656 3331 1002 655 3332 1001 655 3333 1001 651 3334 1004 652 3335 1003 626 3336 972 658 3337 1006 657 3338 1005 657 3339 1005 625 3340 971 626 3341 972 656 3342 1002 632 3343 978 629 3344 975 629 3345 975 655 3346 1001 656 3347 1002 659 3348 1007 647 3349 993 648 3350 994 648 3351 994 660 3352 1008 659 3353 1007 642 3354 988 662 3355 1010 661 3356 1009 661 3357 1009 641 3358 987 642 3359 988 631 3360 977 643 3361 989 644 3362 990 644 3363 990 630 3364 976 631 3365 977 646 3366 992 627 3367 973 628 3368 974 628 3369 974 645 3370 991 646 3371 992 663 3372 1011 639 3373 985 640 3374 986 640 3375 986 664 3376 1012 663 3377 1011 658 3378 1006 663 3379 1011 664 3380 1012 664 3381 1012 657 3382 1005 658 3383 1006 610 3384 956 629 3385 975 630 3386 976 630 3387 976 609 3388 955 610 3389 956 608 3390 954 628 3391 974 625 3392 971 625 3393 971 607 3394 953 608 3395 954 666 3396 1014 665 3397 1013 613 3398 959 613 3399 959 614 3400 960 666 3401 1014 640 3402 986 637 3403 983 611 3404 957 611 3405 957 612 3406 958 640 3407 986 618 3408 964 648 3409 994 645 3410 991 645 3411 991 617 3412 963 618 3413 964 616 3414 962 644 3415 990 641 3416 987 641 3417 987 615 3418 961 616 3419 962 622 3420 968 657 3421 1005 664 3422 1012 664 3423 1012 621 3424 967 622 3425 968 607 3426 953 625 3427 971 657 3428 1005 657 3429 1005 622 3430 968 607 3431 953 619 3432 965 655 3433 1001 629 3434 975 629 3435 975 610 3436 956 619 3437 965 624 3438 970 660 3439 1008 648 3440 994 648 3441 994 618 3442 964 624 3443 970 641 3444 987 661 3445 1009 623 3446 969 623 3447 969 615 3448 961 641 3449 987 645 3450 991 628 3451 974 608 3452 954 608 3453 954 617 3454 963 645 3455 991 630 3456 976 644 3457 990 616 3458 962 616 3459 962 609 3460 955 630 3461 976 621 3462 967 664 3463 1012 640 3464 986 640 3465 986 612 3466 958 621 3467 967 620 3468 966 665 3469 1013 655 3470 1001 649 3471 1016 650 3472 1015 653 3473 999 653 3474 999 654 3475 1000 649 3476 1016 636 3477 982 633 3478 979 665 3479 1013 665 3480 1013 666 3481 1014 636 3482 982 633 3483 979 649 3484 995 654 3485 1017 654 3486 1017 665 3487 1013 633 3488 979 665 3489 1013 620 3490 966 613 3491 959 620 3492 966 655 3493 1001 619 3494 965 651 3495 1004 655 3496 1001 665 3497 1013 665 3498 1013 654 3499 1017 651 3500 1004 667 3501 1018 670 3502 1021 669 3503 1020 669 3504 1020 668 3505 1019 667 3506 1018 614 3507 1023 611 3508 1022 672 3509 1025 672 3510 1025 671 3511 1024 614 3512 1023 673 3513 1026 676 3514 1029 675 3515 1028 675 3516 1028 674 3517 1027 673 3518 1026 677 3519 1030 680 3520 1033 679 3521 1032 679 3522 1032 678 3523 1031 677 3524 1030 668 3525 1019 677 3526 1030 678 3527 1031 678 3528 1031 667 3529 1018 668 3530 1019 623 3531 1034 673 3532 1026 674 3533 1027 674 3534 1027 624 3535 1035 623 3536 1034 675 3537 1028 676 3538 1029 669 3539 1020 669 3540 1020 670 3541 1021 675 3542 1028 680 3543 1033 671 3544 1024 672 3545 1025 672 3546 1025 679 3547 1032 680 3548 1033 683 3549 1038 682 3550 1037 681 3551 1036 681 3552 1036 684 3553 1039 683 3554 1038 686 3555 1041 685 3556 1040 688 3557 1043 688 3558 1043 687 3559 1042 686 3560 1041 635 3561 1046 636 3562 1045 689 3563 1044 689 3564 1044 690 3565 1047 635 3566 1046 692 3567 1050 691 3568 1049 637 3569 1048 637 3570 1048 638 3571 1051 692 3572 1050 695 3573 1054 694 3574 1053 693 3575 1052 693 3576 1052 696 3577 1055 695 3578 1054 699 3579 1058 698 3580 1057 697 3581 1056 697 3582 1056 700 3583 1059 699 3584 1058 690 3585 1047 689 3586 1044 701 3587 1060 701 3588 1060 606 3589 1061 690 3590 1047 703 3591 1063 702 3592 1062 604 3593 1065 604 3594 1065 704 3595 1064 703 3596 1063 604 3597 1068 702 3598 1067 705 3599 1066 705 3600 1066 706 3601 1069 604 3602 1068 684 3603 1039 681 3604 1036 707 3605 1070 707 3606 1070 708 3607 1071 684 3608 1039 706 3609 1069 705 3610 1066 685 3611 1040 685 3612 1040 686 3613 1041 706 3614 1069 659 3615 1073 660 3616 1072 698 3617 1057 698 3618 1057 699 3619 1058 659 3620 1073 696 3621 1055 693 3622 1052 661 3623 1074 661 3624 1074 662 3625 1075 696 3626 1055 687 3627 1042 688 3628 1043 694 3629 1053 694 3630 1053 695 3631 1054 687 3632 1042 700 3633 1059 697 3634 1056 682 3635 1037 682 3636 1037 683 3637 1038 700 3638 1059 710 3639 1077 709 3640 1076 691 3641 1049 691 3642 1049 692 3643 1050 710 3644 1077 708 3645 1071 707 3646 1070 709 3647 1076 709 3648 1076 710 3649 1077 708 3650 1071 668 3651 1019 669 3652 1020 688 3653 1043 688 3654 1043 685 3655 1040 668 3656 1019 670 3657 1021 667 3658 1018 681 3659 1036 681 3660 1036 682 3661 1037 670 3662 1021 666 3663 1078 614 3664 1023 671 3665 1024 671 3666 1024 711 3667 1079 666 3668 1078 691 3669 1049 672 3670 1025 611 3671 1022 611 3672 1022 637 3673 1048 691 3674 1049 674 3675 1027 675 3676 1028 697 3677 1056 697 3678 1056 698 3679 1057 674 3680 1027 676 3681 1029 673 3682 1026 693 3683 1052 693 3684 1052 694 3685 1053 676 3686 1029 678 3687 1031 679 3688 1032 709 3689 1076 709 3690 1076 707 3691 1070 678 3692 1031 667 3693 1018 678 3694 1031 707 3695 1070 707 3696 1070 681 3697 1036 667 3698 1018 677 3699 1030 668 3700 1019 685 3701 1040 685 3702 1040 705 3703 1066 677 3704 1030 624 3705 1035 674 3706 1027 698 3707 1057 698 3708 1057 660 3709 1072 624 3710 1035 693 3711 1052 673 3712 1026 623 3713 1034 623 3714 1034 661 3715 1074 693 3716 1052 697 3717 1056 675 3718 1028 670 3719 1021 670 3720 1021 682 3721 1037 697 3722 1056 688 3723 1043 669 3724 1020 676 3725 1029 676 3726 1029 694 3727 1053 688 3728 1043 679 3729 1032 672 3730 1025 691 3731 1049 691 3732 1049 709 3733 1076 679 3734 1032 680 3735 1033 705 3736 1066 711 3737 1079 701 3738 1080 703 3739 1063 704 3740 1064 704 3741 1064 606 3742 1081 701 3743 1080 636 3744 1045 666 3745 1078 711 3746 1079 711 3747 1079 689 3748 1044 636 3749 1045 689 3750 1044 711 3751 1079 703 3752 1082 703 3753 1082 701 3754 1060 689 3755 1044 711 3756 1079 671 3757 1024 680 3758 1033 680 3759 1033 677 3760 1030 705 3761 1066 702 3762 1067 703 3763 1082 711 3764 1079 711 3765 1079 705 3766 1066 702 3767 1067 715 3768 1086 714 3769 1085 713 3770 1084 713 3771 1084 712 3772 1083 715 3773 1086 719 3774 1090 718 3775 1089 717 3776 1088 717 3777 1088 716 3778 1087 719 3779 1090 713 3780 1084 714 3781 1085 721 3782 1092 721 3783 1092 720 3784 1091 713 3785 1084 718 3786 1089 723 3787 1094 722 3788 1093 722 3789 1093 717 3790 1088 718 3791 1089 726 3792 1097 725 3793 1096 724 3794 1095 724 3795 1095 727 3796 1098 726 3797 1097 729 3798 1100 728 3799 1099 725 3800 1096 725 3801 1096 726 3802 1097 729 3803 1100 725 3804 1096 717 3805 1088 722 3806 1093 722 3807 1093 724 3808 1095 725 3809 1096 728 3810 1099 716 3811 1087 717 3812 1088 717 3813 1088 725 3814 1096 728 3815 1099 730 3816 1101 733 3817 1104 732 3818 1103 732 3819 1103 731 3820 1102 730 3821 1101 732 3822 1103 735 3823 1106 734 3824 1105 734 3825 1105 731 3826 1102 732 3827 1103 733 3828 1104 730 3829 1101 737 3830 1108 737 3831 1108 736 3832 1107 733 3833 1104 262 3834 1112 740 3835 1111 739 3836 1110 739 3837 1110 738 3838 1109 262 3839 1112 741 3840 1113 743 3841 1117 736 3842 1116 741 3843 1113 736 3844 1116 737 3845 1115 741 3846 1113 737 3847 1115 742 3848 1114 742 3849 1114 745 3850 1119 744 3851 1118 744 3852 1118 741 3853 1113 742 3854 1114 745 3855 1119 747 3856 1121 746 3857 1120 746 3858 1120 744 3859 1118 745 3860 1119 747 3861 1121 749 3862 1123 748 3863 1122 748 3864 1122 746 3865 1120 747 3866 1121 748 3867 1122 749 3868 1123 751 3869 1125 751 3870 1125 750 3871 1124 748 3872 1122 750 3873 1124 751 3874 1125 753 3875 1127 753 3876 1127 752 3877 1126 750 3878 1124 755 3879 1131 513 3880 1130 514 3881 1129 514 3882 1129 754 3883 1128 755 3884 1131 756 3885 1132 734 3886 1105 735 3887 1106 735 3888 1106 757 3889 1133 756 3890 1132 758 3891 1134 761 3892 1137 760 3893 1136 760 3894 1136 759 3895 1135 758 3896 1134 759 3897 1135 760 3898 1136 763 3899 1139 763 3900 1139 762 3901 1138 759 3902 1135 764 3903 1140 766 3904 1144 755 3905 1143 764 3906 1140 755 3907 1143 754 3908 1142 764 3909 1140 754 3910 1142 765 3911 1141 765 3912 1141 768 3913 1146 767 3914 1145 767 3915 1145 764 3916 1140 765 3917 1141 768 3918 1146 770 3919 1148 769 3920 1147 769 3921 1147 767 3922 1145 768 3923 1146 770 3924 1148 761 3925 1137 758 3926 1134 758 3927 1134 769 3928 1147 770 3929 1148 771 3930 1149 716 3931 1087 728 3932 1099 728 3933 1099 772 3934 1150 771 3935 1149 772 3936 1150 728 3937 1099 729 3938 1100 729 3939 1100 773 3940 1151 772 3941 1150 776 3942 1155 299 3943 1154 775 3944 1153 775 3945 1153 774 3946 1152 776 3947 1155 777 3948 1156 780 3949 1159 779 3950 1158 779 3951 1158 778 3952 1157 777 3953 1156 781 3954 1160 782 3955 1161 777 3956 1156 777 3957 1156 778 3958 1157 781 3959 1160 783 3960 1162 784 3961 1163 782 3962 1161 782 3963 1161 781 3964 1160 783 3965 1162 785 3966 1164 786 3967 1165 784 3968 1163 784 3969 1163 783 3970 1162 785 3971 1164 787 3972 1166 788 3973 1167 786 3974 1165 786 3975 1165 785 3976 1164 787 3977 1166 548 3978 1171 549 3979 1170 790 3980 1169 790 3981 1169 789 3982 1168 548 3983 1171 549 3984 1170 551 3985 1173 791 3986 1172 791 3987 1172 790 3988 1169 549 3989 1170 792 3990 1174 793 3991 1175 724 3992 1095 724 3993 1095 722 3994 1093 792 3995 1174 727 3996 1098 724 3997 1095 793 3998 1175 793 3999 1175 794 4000 1176 727 4001 1098 795 4002 1177 798 4003 1180 797 4004 1179 797 4005 1179 796 4006 1178 795 4007 1177 799 4008 1181 798 4009 1180 795 4010 1177 795 4011 1177 800 4012 1182 799 4013 1181 801 4014 1183 802 4015 1184 799 4016 1181 799 4017 1181 800 4018 1182 801 4019 1183 803 4020 1185 802 4021 1184 801 4022 1183 801 4023 1183 804 4024 1186 803 4025 1185 796 4026 1178 797 4027 1179 806 4028 1188 806 4029 1188 805 4030 1187 796 4031 1178 262 4032 1112 738 4033 1109 753 4034 1190 753 4035 1190 332 4036 1189 262 4037 1112 739 4038 1193 807 4039 1192 752 4040 1126 738 4041 1191 739 4042 1193 752 4043 1126 738 4044 1191 752 4045 1126 753 4046 1127 752 4047 1197 807 4048 1196 743 4049 1195 743 4050 1195 741 4051 1194 752 4052 1197 761 4053 1201 809 4054 1200 808 4055 1199 808 4056 1199 760 4057 1198 761 4058 1201 757 4059 1204 810 4060 1203 762 4061 1138 756 4062 1202 757 4063 1204 762 4064 1138 756 4065 1202 762 4066 1138 763 4067 1139 766 4068 1205 764 4069 1208 762 4070 1207 762 4071 1207 810 4072 1206 766 4073 1205 778 4074 1209 813 4075 1212 812 4076 1211 812 4077 1211 811 4078 1210 778 4079 1209 776 4080 1215 774 4081 1214 814 4082 1213 815 4083 1216 776 4084 1215 814 4085 1213 780 4086 1159 815 4087 1216 814 4088 1213 780 4089 1159 814 4090 1213 779 4091 1158 771 4092 1217 772 4093 1220 773 4094 1219 771 4095 1217 773 4096 1219 816 4097 1218 771 4098 1217 816 4099 1218 788 4100 1167 771 4101 1217 788 4102 1167 787 4103 1166 780 4104 1221 788 4105 1224 816 4106 1223 816 4107 1223 815 4108 1222 780 4109 1221 578 4110 1225 951 4111 1445 815 4112 1226 723 4113 1094 805 4114 1229 792 4115 1174 792 4116 1174 722 4117 1093 723 4118 1094 789 4119 1233 790 4120 1232 791 4121 1231 804 4122 1186 789 4123 1233 791 4124 1231 803 4125 1185 804 4126 1186 791 4127 1231 803 4128 1185 791 4129 1231 817 4130 1230 818 4131 1234 806 4132 1237 803 4133 1236 803 4134 1236 817 4135 1235 818 4136 1234 794 4137 1238 793 4138 1241 792 4139 1240 794 4140 1238 792 4141 1240 805 4142 1187 794 4143 1238 805 4144 1187 806 4145 1188 794 4146 1238 806 4147 1188 818 4148 1239 814 4149 1243 774 4150 1152 775 4151 1153 775 4152 1153 343 4153 1242 814 4154 1243 816 4155 1244 773 4156 1249 729 4157 1248 727 4158 1247 794 4159 1246 818 4160 1245 729 4161 1248 727 4162 1247 818 4163 1245 816 4164 1244 729 4165 1248 818 4166 1245 729 4167 1248 726 4168 1250 727 4169 1247 816 4170 1244 818 4171 1245 578 4172 1225 817 4173 1251 791 4174 1254 551 4175 1253 551 4176 1253 582 4177 1252 817 4178 1251 747 4179 1258 820 4180 1257 819 4181 1256 819 4182 1256 749 4183 1255 747 4184 1258 819 4185 1256 820 4186 1257 783 4187 1260 783 4188 1260 781 4189 1259 819 4190 1256 742 4191 1262 720 4192 1091 721 4193 1092 721 4194 1092 745 4195 1261 742 4196 1262 716 4197 1087 771 4198 1149 787 4199 1263 787 4200 1263 719 4201 1090 716 4202 1087 783 4203 1260 820 4204 1257 821 4205 1265 821 4206 1265 785 4207 1264 783 4208 1260 821 4209 1265 820 4210 1257 747 4211 1258 747 4212 1258 745 4213 1261 821 4214 1265 749 4215 1255 819 4216 1256 811 4217 1210 811 4218 1210 751 4219 1266 749 4220 1255 811 4221 1210 819 4222 1256 781 4223 1259 781 4224 1259 778 4225 1209 811 4226 1210 779 4227 1268 822 4228 1267 813 4229 1212 813 4230 1212 778 4231 1209 779 4232 1268 751 4233 1266 823 4234 1269 332 4235 1189 332 4236 1189 753 4237 1190 751 4238 1266 785 4239 1264 824 4240 1270 719 4241 1090 719 4242 1090 787 4243 1263 785 4244 1264 824 4245 1270 825 4246 1271 718 4247 1089 718 4248 1089 719 4249 1090 824 4250 1270 825 4251 1271 826 4252 1272 723 4253 1094 723 4254 1094 718 4255 1089 825 4256 1271 826 4257 1272 796 4258 1273 805 4259 1229 805 4260 1229 723 4261 1094 826 4262 1272 785 4263 1264 821 4264 1265 827 4265 1274 827 4266 1274 824 4267 1270 785 4268 1264 827 4269 1274 828 4270 1275 825 4271 1271 825 4272 1271 824 4273 1270 827 4274 1274 828 4275 1275 829 4276 1276 826 4277 1272 826 4278 1272 825 4279 1271 828 4280 1275 809 4281 1200 795 4282 1277 796 4283 1273 796 4284 1273 808 4285 1199 809 4286 1200 761 4287 1201 770 4288 1279 830 4289 1278 830 4290 1278 809 4291 1200 761 4292 1201 830 4293 1278 800 4294 1280 795 4295 1277 795 4296 1277 809 4297 1200 830 4298 1278 829 4299 1276 808 4300 1199 796 4301 1273 796 4302 1273 826 4303 1272 829 4304 1276 715 4305 1086 712 4306 1083 763 4307 1281 763 4308 1281 760 4309 1198 715 4310 1086 808 4311 1199 829 4312 1276 715 4313 1086 715 4314 1086 760 4315 1198 808 4316 1199 829 4317 1276 828 4318 1275 714 4319 1085 714 4320 1085 715 4321 1086 829 4322 1276 714 4323 1085 828 4324 1275 827 4325 1274 827 4326 1274 721 4327 1092 714 4328 1085 745 4329 1261 721 4330 1092 827 4331 1274 827 4332 1274 821 4333 1265 745 4334 1261 742 4335 1262 737 4336 1108 730 4337 1101 730 4338 1101 720 4339 1091 742 4340 1262 720 4341 1091 730 4342 1101 731 4343 1102 731 4344 1102 713 4345 1084 720 4346 1091 731 4347 1102 734 4348 1105 712 4349 1083 712 4350 1083 713 4351 1084 731 4352 1102 734 4353 1105 756 4354 1132 763 4355 1281 763 4356 1281 712 4357 1083 734 4358 1105 595 4359 1285 596 4360 1284 831 4361 1283 831 4362 1283 768 4363 1282 595 4364 1285 548 4365 1171 789 4366 1168 804 4367 1287 804 4368 1287 598 4369 1286 548 4370 1171 800 4371 1280 830 4372 1278 831 4373 1283 831 4374 1283 801 4375 1288 800 4376 1280 831 4377 1283 830 4378 1278 770 4379 1279 770 4380 1279 768 4381 1282 831 4382 1283 765 4383 1290 599 4384 1289 595 4385 1285 595 4386 1285 768 4387 1282 765 4388 1290 765 4389 1290 754 4390 1128 514 4391 1129 514 4392 1129 599 4393 1289 765 4394 1290 801 4395 1288 600 4396 1291 598 4397 1286 598 4398 1286 804 4399 1287 801 4400 1288 801 4401 1288 831 4402 1283 596 4403 1284 596 4404 1284 600 4405 1291 801 4406 1288 814 4407 1243 343 4408 1242 822 4409 1267 822 4410 1267 779 4411 1268 814 4412 1243 751 4413 1266 811 4414 1210 812 4415 1211 812 4416 1211 823 4417 1269 751 4418 1266 818 4419 1245 817 4420 1251 578 4421 1225 578 4422 1225 815 4423 1226 816 4424 1244 817 4425 1251 582 4426 1252 578 4427 1225 777 4428 1293 786 4429 1292 788 4430 1224 788 4431 1224 780 4432 1221 777 4433 1293 782 4434 1295 784 4435 1294 786 4436 1292 786 4437 1292 777 4438 1293 782 4439 1295 746 4440 1299 748 4441 1298 750 4442 1297 750 4443 1297 744 4444 1296 746 4445 1299 744 4446 1296 750 4447 1297 752 4448 1197 752 4449 1197 741 4450 1194 744 4451 1296 767 4452 1301 759 4453 1300 762 4454 1207 762 4455 1207 764 4456 1208 767 4457 1301 769 4458 1303 758 4459 1302 759 4460 1300 759 4461 1300 767 4462 1301 769 4463 1303 797 4464 1305 802 4465 1304 803 4466 1236 803 4467 1236 806 4468 1237 797 4469 1305 798 4470 1307 799 4471 1306 802 4472 1304 802 4473 1304 797 4474 1305 798 4475 1307 835 4476 1311 834 4477 1310 949 4478 1309 949 4479 1309 832 4480 1308 835 4481 1311 837 4482 1313 950 4483 1312 834 4484 1310 834 4485 1310 835 4486 1311 837 4487 1313 838 4488 1314 841 4489 1317 840 4490 1316 840 4491 1316 839 4492 1315 838 4493 1314 843 4494 1319 842 4495 1318 845 4496 1321 845 4497 1321 844 4498 1320 843 4499 1319 846 4500 1322 849 4501 1325 848 4502 1324 848 4503 1324 847 4504 1323 846 4505 1322 850 4506 1326 853 4507 1329 852 4508 1328 852 4509 1328 851 4510 1327 850 4511 1326 839 4512 1315 850 4513 1326 851 4514 1327 851 4515 1327 838 4516 1314 839 4517 1315 854 4518 1330 846 4519 1322 847 4520 1323 847 4521 1323 855 4522 1331 854 4523 1330 848 4524 1324 849 4525 1325 840 4526 1316 840 4527 1316 841 4528 1317 848 4529 1324 853 4530 1329 844 4531 1320 845 4532 1321 845 4533 1321 852 4534 1328 853 4535 1329 858 4536 1334 857 4537 1333 856 4538 1332 856 4539 1332 859 4540 1335 858 4541 1334 861 4542 1337 860 4543 1336 863 4544 1339 863 4545 1339 862 4546 1338 861 4547 1337 866 4548 1342 865 4549 1341 864 4550 1340 864 4551 1340 867 4552 1343 866 4553 1342 870 4554 1346 869 4555 1345 868 4556 1344 868 4557 1344 871 4558 1347 870 4559 1346 874 4560 1350 873 4561 1349 872 4562 1348 872 4563 1348 875 4564 1351 874 4565 1350 878 4566 1354 877 4567 1353 876 4568 1352 876 4569 1352 879 4570 1355 878 4571 1354 867 4572 1343 864 4573 1340 880 4574 1356 880 4575 1356 881 4576 1357 867 4577 1343 883 4578 1359 882 4579 1358 885 4580 1361 885 4581 1361 884 4582 1360 883 4583 1359 885 4584 1364 882 4585 1363 886 4586 1362 886 4587 1362 887 4588 1365 885 4589 1364 859 4590 1335 856 4591 1332 888 4592 1366 888 4593 1366 889 4594 1367 859 4595 1335 887 4596 1365 886 4597 1362 860 4598 1336 860 4599 1336 861 4600 1337 887 4601 1365 891 4602 1369 890 4603 1368 877 4604 1353 877 4605 1353 878 4606 1354 891 4607 1369 875 4608 1351 872 4609 1348 892 4610 1370 892 4611 1370 893 4612 1371 875 4613 1351 862 4614 1338 863 4615 1339 873 4616 1349 873 4617 1349 874 4618 1350 862 4619 1338 879 4620 1355 876 4621 1352 857 4622 1333 857 4623 1333 858 4624 1334 879 4625 1355 895 4626 1373 894 4627 1372 869 4628 1345 869 4629 1345 870 4630 1346 895 4631 1373 889 4632 1367 888 4633 1366 894 4634 1372 894 4635 1372 895 4636 1373 889 4637 1367 839 4638 1315 840 4639 1316 863 4640 1339 863 4641 1339 860 4642 1336 839 4643 1315 841 4644 1317 838 4645 1314 856 4646 1332 856 4647 1332 857 4648 1333 841 4649 1317 896 4650 1374 843 4651 1319 844 4652 1320 844 4653 1320 897 4654 1375 896 4655 1374 869 4656 1345 845 4657 1321 842 4658 1318 842 4659 1318 868 4660 1344 869 4661 1345 847 4662 1323 848 4663 1324 876 4664 1352 876 4665 1352 877 4666 1353 847 4667 1323 849 4668 1325 846 4669 1322 872 4670 1348 872 4671 1348 873 4672 1349 849 4673 1325 851 4674 1327 852 4675 1328 894 4676 1372 894 4677 1372 888 4678 1366 851 4679 1327 838 4680 1314 851 4681 1327 888 4682 1366 888 4683 1366 856 4684 1332 838 4685 1314 850 4686 1326 839 4687 1315 860 4688 1336 860 4689 1336 886 4690 1362 850 4691 1326 855 4692 1331 847 4693 1323 877 4694 1353 877 4695 1353 890 4696 1368 855 4697 1331 872 4698 1348 846 4699 1322 854 4700 1330 854 4701 1330 892 4702 1370 872 4703 1348 876 4704 1352 848 4705 1324 841 4706 1317 841 4707 1317 857 4708 1333 876 4709 1352 863 4710 1339 840 4711 1316 849 4712 1325 849 4713 1325 873 4714 1349 863 4715 1339 852 4716 1328 845 4717 1321 869 4718 1345 869 4719 1345 894 4720 1372 852 4721 1328 853 4722 1329 886 4723 1362 897 4724 1375 880 4725 1376 883 4726 1359 884 4727 1360 884 4728 1360 881 4729 1377 880 4730 1376 865 4731 1341 896 4732 1374 897 4733 1375 897 4734 1375 864 4735 1340 865 4736 1341 864 4737 1340 897 4738 1375 883 4739 1378 883 4740 1378 880 4741 1356 864 4742 1340 897 4743 1375 844 4744 1320 853 4745 1329 853 4746 1329 850 4747 1326 886 4748 1362 882 4749 1363 883 4750 1378 897 4751 1375 897 4752 1375 886 4753 1362 882 4754 1363 898 4755 1379 901 4756 1382 900 4757 1381 900 4758 1381 899 4759 1380 898 4760 1379 843 4761 1386 903 4762 1385 902 4763 1384 902 4764 1384 842 4765 1383 843 4766 1386 904 4767 1387 907 4768 1390 906 4769 1389 906 4770 1389 905 4771 1388 904 4772 1387 908 4773 1391 911 4774 1394 910 4775 1393 910 4776 1393 909 4777 1392 908 4778 1391 901 4779 1382 898 4780 1379 911 4781 1394 911 4782 1394 908 4783 1391 901 4784 1382 854 4785 1395 855 4786 1396 907 4787 1390 907 4788 1390 904 4789 1387 854 4790 1395 906 4791 1389 899 4792 1380 900 4793 1381 900 4794 1381 905 4795 1388 906 4796 1389 909 4797 1392 910 4798 1393 902 4799 1384 902 4800 1384 903 4801 1385 909 4802 1392 914 4803 1399 913 4804 1398 912 4805 1397 912 4806 1397 915 4807 1400 914 4808 1399 919 4809 1404 918 4810 1403 917 4811 1402 917 4812 1402 916 4813 1401 919 4814 1404 866 4815 1407 921 4816 1406 920 4817 1405 920 4818 1405 865 4819 1408 866 4820 1407 922 4821 1411 871 4822 1410 868 4823 1409 868 4824 1409 923 4825 1412 922 4826 1411 926 4827 1415 925 4828 1414 924 4829 1413 924 4830 1413 927 4831 1416 926 4832 1415 930 4833 1419 929 4834 1418 928 4835 1417 928 4836 1417 931 4837 1420 930 4838 1419 921 4839 1406 836 4840 1422 932 4841 1421 932 4842 1421 920 4843 1405 921 4844 1406 935 4845 1426 934 4846 1425 833 4847 1424 833 4848 1424 933 4849 1423 935 4850 1426 833 4851 1429 937 4852 1428 936 4853 1427 936 4854 1427 933 4855 1430 833 4856 1429 913 4857 1398 939 4858 1432 938 4859 1431 938 4860 1431 912 4861 1397 913 4862 1398 937 4863 1428 919 4864 1404 916 4865 1401 916 4866 1401 936 4867 1427 937 4868 1428 891 4869 1433 930 4870 1419 931 4871 1420 931 4872 1420 890 4873 1434 891 4874 1433 925 4875 1414 893 4876 1436 892 4877 1435 892 4878 1435 924 4879 1413 925 4880 1414 918 4881 1403 926 4882 1415 927 4883 1416 927 4884 1416 917 4885 1402 918 4886 1403 929 4887 1418 914 4888 1399 915 4889 1400 915 4890 1400 928 4891 1417 929 4892 1418 940 4893 1437 922 4894 1411 923 4895 1412 923 4896 1412 941 4897 1438 940 4898 1437 939 4899 1432 940 4900 1437 941 4901 1438 941 4902 1438 938 4903 1431 939 4904 1432 901 4905 1382 916 4906 1401 917 4907 1402 917 4908 1402 900 4909 1381 901 4910 1382 899 4911 1380 915 4912 1400 912 4913 1397 912 4914 1397 898 4915 1379 899 4916 1380 896 4917 1440 942 4918 1439 903 4919 1385 903 4920 1385 843 4921 1386 896 4922 1440 923 4923 1412 868 4924 1409 842 4925 1383 842 4926 1383 902 4927 1384 923 4928 1412 907 4929 1390 931 4930 1420 928 4931 1417 928 4932 1417 906 4933 1389 907 4934 1390 905 4935 1388 927 4936 1416 924 4937 1413 924 4938 1413 904 4939 1387 905 4940 1388 911 4941 1394 938 4942 1431 941 4943 1438 941 4944 1438 910 4945 1393 911 4946 1394 898 4947 1379 912 4948 1397 938 4949 1431 938 4950 1431 911 4951 1394 898 4952 1379 908 4953 1391 936 4954 1427 916 4955 1401 916 4956 1401 901 4957 1382 908 4958 1391 855 4959 1396 890 4960 1434 931 4961 1420 931 4962 1420 907 4963 1390 855 4964 1396 924 4965 1413 892 4966 1435 854 4967 1395 854 4968 1395 904 4969 1387 924 4970 1413 928 4971 1417 915 4972 1400 899 4973 1380 899 4974 1380 906 4975 1389 928 4976 1417 917 4977 1402 927 4978 1416 905 4979 1388 905 4980 1388 900 4981 1381 917 4982 1402 910 4983 1393 941 4984 1438 923 4985 1412 923 4986 1412 902 4987 1384 910 4988 1393 909 4989 1392 942 4990 1439 936 4991 1427 932 4992 1442 836 4993 1441 934 4994 1425 934 4995 1425 935 4996 1426 932 4997 1442 865 4998 1408 920 4999 1405 942 5000 1439 942 5001 1439 896 5002 1440 865 5003 1408 920 5004 1405 932 5005 1421 935 5006 1443 935 5007 1443 942 5008 1439 920 5009 1405 942 5010 1439 909 5011 1392 903 5012 1385 909 5013 1392 936 5014 1427 908 5015 1391 933 5016 1430 936 5017 1427 942 5018 1439 942 5019 1439 935 5020 1443 933 5021 1430 299 5022 504 951 5023 1444 338 5024 506 338 5025 506 298 5026 505 299 5027 504 299 5028 1228 776 5029 1227 815 5030 1226 815 5031 1226 951 5032 1445 299 5033 1228 54 5034 188 578 5035 176 952 5036 1447 952 5037 1446 578 5038 864 575 5039 867 984 5040 1546 1073 5041 1547 978 5042 1548 984 5043 1546 978 5044 1548 982 5045 1550 983 5046 1545 984 5047 1546 982 5048 1550 1005 5049 1544 983 5050 1545 982 5051 1550 1015 5052 1464 1016 5053 1465 970 5054 1466 970 5055 1466 971 5056 1449 1015 5057 1464 1019 5058 1484 1020 5059 1495 995 5060 1501 995 5061 1501 956 5062 1455 1019 5063 1484 992 5064 1448 1023 5065 1454 1019 5066 1480 1019 5067 1480 956 5068 1483 992 5069 1448 980 5070 1553 1088 5071 1554 1008 5072 1555 981 5073 1552 980 5074 1553 1008 5075 1555 993 5076 1551 981 5077 1552 1008 5078 1555 993 5079 1551 1008 5080 1555 957 5081 1556 979 5082 1456 984 5083 1482 983 5084 1485 983 5085 1485 955 5086 1453 979 5087 1456 958 5088 1451 991 5089 1452 1094 5090 1458 1094 5091 1458 1009 5092 1460 958 5093 1451 954 5094 1486 1097 5095 1487 1098 5096 1524 1098 5097 1524 997 5098 1481 954 5099 1486 968 5100 1471 959 5101 1474 953 5102 1477 953 5103 1477 965 5104 1497 968 5105 1471 975 5106 1516 976 5107 1517 977 5108 1518 977 5109 1518 974 5110 1519 975 5111 1516 966 5112 1520 967 5113 1521 964 5114 1522 964 5115 1522 963 5116 1523 966 5117 1520 965 5118 1472 953 5119 1457 996 5120 1529 996 5121 1529 962 5122 1461 965 5123 1472 974 5124 1473 977 5125 1478 972 5126 1479 972 5127 1479 973 5128 1488 974 5129 1473 963 5130 1489 964 5131 1490 961 5132 1463 961 5133 1463 960 5134 1462 963 5135 1489 966 5136 1520 963 5137 1523 971 5138 1449 971 5139 1449 970 5140 1466 966 5141 1520 963 5142 1489 960 5143 1462 969 5144 1499 969 5145 1499 971 5146 1502 963 5147 1489 961 5148 1463 964 5149 1490 974 5150 1473 974 5151 1473 973 5152 1488 961 5153 1463 964 5154 1522 967 5155 1521 975 5156 1516 975 5157 1516 974 5158 1519 964 5159 1522 967 5160 1450 968 5161 1459 976 5162 1467 976 5163 1467 975 5164 1468 967 5165 1450 968 5166 1471 965 5167 1497 977 5168 1518 977 5169 1518 976 5170 1517 968 5171 1471 965 5172 1472 962 5173 1461 972 5174 1479 972 5175 1479 977 5176 1478 965 5177 1472 991 5178 1452 997 5179 1481 1098 5180 1524 1098 5181 1524 1094 5182 1458 991 5183 1452 994 5184 1509 957 5185 1511 1008 5186 1527 1008 5187 1527 1118 5188 1507 994 5189 1509 954 5190 1494 994 5191 1525 1118 5192 1526 1118 5193 1526 1097 5194 1491 954 5195 1494 987 5196 1493 988 5197 1496 989 5198 1503 989 5199 1503 990 5200 1504 987 5201 1493 955 5202 1558 995 5203 1559 1020 5204 1560 1020 5205 1560 979 5206 1557 955 5207 1558 971 5208 1502 969 5209 1499 1006 5210 1515 1006 5211 1515 1015 5212 1514 971 5213 1502 1023 5214 1469 992 5215 1470 959 5216 1475 1023 5217 1469 959 5218 1475 968 5219 1459 1023 5220 1469 968 5221 1459 967 5222 1450 1023 5223 1469 967 5224 1450 966 5225 1476 1023 5226 1469 966 5227 1476 1007 5228 1492 1007 5229 1492 966 5230 1476 970 5231 1498 970 5232 1498 1016 5233 1500 1007 5234 1492 981 5235 1505 993 5236 1506 982 5237 1513 982 5238 1513 985 5239 1508 981 5240 1505 982 5241 1513 978 5242 1510 986 5243 1512 986 5244 1512 985 5245 1508 982 5246 1513 1088 5247 1528 980 5248 1530 986 5249 1512 986 5250 1512 978 5251 1510 1088 5252 1528 980 5253 1553 981 5254 1552 988 5255 1561 988 5256 1561 987 5257 1562 980 5258 1553 981 5259 1565 985 5260 1566 989 5261 1503 989 5262 1503 988 5263 1567 981 5264 1565 985 5265 1566 986 5266 1568 990 5267 1504 990 5268 1504 989 5269 1503 985 5270 1566 986 5271 1568 980 5272 1569 987 5273 1570 987 5274 1570 990 5275 1504 986 5276 1568 1004 5277 1533 959 5278 1534 992 5279 1531 992 5280 1531 999 5281 1532 1004 5282 1533 1002 5283 1549 957 5284 1511 994 5285 1509 994 5286 1509 1001 5287 1541 1002 5288 1549 1001 5289 1540 994 5290 1525 954 5291 1494 954 5292 1494 999 5293 1538 1001 5294 1540 1002 5295 1564 995 5296 1559 955 5297 1558 955 5298 1558 1000 5299 1563 1002 5300 1564 1005 5301 1542 982 5302 1513 993 5303 1506 993 5304 1506 1000 5305 1539 1005 5306 1542 998 5307 1536 991 5308 1452 958 5309 1451 958 5310 1451 1003 5311 1535 998 5312 1536 998 5313 1536 953 5314 1537 959 5315 1534 959 5316 1534 1004 5317 1533 998 5318 1536 997 5319 1481 1004 5320 1533 999 5321 1532 999 5322 1532 954 5323 1486 997 5324 1481 995 5325 1501 1002 5326 1549 1001 5327 1541 1001 5328 1541 956 5329 1455 995 5330 1501 956 5331 1483 1001 5332 1540 999 5333 1538 999 5334 1538 992 5335 1448 956 5336 1483 957 5337 1572 1002 5338 1564 1000 5339 1563 1000 5340 1563 993 5341 1571 957 5342 1572 983 5343 1485 1005 5344 1542 1000 5345 1539 1000 5346 1539 955 5347 1453 983 5348 1485 953 5349 1537 998 5350 1536 1003 5351 1535 1003 5352 1535 996 5353 1543 953 5354 1537 991 5355 1452 998 5356 1536 1004 5357 1533 1004 5358 1533 997 5359 1481 991 5360 1452 1012 5361 1577 1073 5362 1576 984 5363 1575 1013 5364 1578 1012 5365 1577 984 5366 1575 1013 5367 1578 984 5368 1575 1011 5369 1574 1010 5370 1573 1013 5371 1578 1011 5372 1574 1015 5373 1580 1014 5374 1579 1017 5375 1582 1017 5376 1582 1016 5377 1581 1015 5378 1580 1019 5379 1584 1018 5380 1583 1021 5381 1586 1021 5382 1586 1020 5383 1585 1019 5384 1584 1022 5385 1587 1018 5386 1590 1019 5387 1589 1019 5388 1589 1023 5389 1588 1022 5390 1587 1024 5391 1591 1028 5392 1596 1027 5393 1595 1027 5394 1595 1145 5395 1594 1026 5396 1593 1027 5397 1595 1026 5398 1593 1025 5399 1592 1024 5400 1591 1027 5401 1595 1025 5402 1592 979 5403 1598 1029 5404 1597 1011 5405 1600 1011 5406 1600 984 5407 1599 979 5408 1598 1030 5409 1601 1033 5410 1604 1032 5411 1603 1032 5412 1603 1031 5413 1602 1030 5414 1601 1035 5415 1606 1034 5416 1605 1152 5417 1608 1152 5418 1608 1153 5419 1607 1035 5420 1606 1036 5421 1609 1039 5422 1612 1038 5423 1611 1038 5424 1611 1037 5425 1610 1036 5426 1609 1040 5427 1613 1043 5428 1616 1042 5429 1615 1042 5430 1615 1041 5431 1614 1040 5432 1613 1044 5433 1617 1047 5434 1620 1046 5435 1619 1046 5436 1619 1045 5437 1618 1044 5438 1617 1039 5439 1621 1049 5440 1624 1048 5441 1623 1048 5442 1623 1038 5443 1622 1039 5444 1621 1043 5445 1625 1051 5446 1628 1050 5447 1627 1050 5448 1627 1042 5449 1626 1043 5450 1625 1047 5451 1629 1053 5452 1632 1052 5453 1631 1052 5454 1631 1046 5455 1630 1047 5456 1629 1044 5457 1617 1017 5458 1582 1014 5459 1579 1014 5460 1579 1047 5461 1620 1044 5462 1617 1047 5463 1629 1014 5464 1634 1054 5465 1633 1054 5466 1633 1053 5467 1632 1047 5468 1629 1052 5469 1631 1051 5470 1628 1043 5471 1625 1043 5472 1625 1046 5473 1630 1052 5474 1631 1046 5475 1619 1043 5476 1616 1040 5477 1613 1040 5478 1613 1045 5479 1618 1046 5480 1619 1045 5481 1635 1040 5482 1638 1041 5483 1637 1041 5484 1637 1036 5485 1636 1045 5486 1635 1036 5487 1609 1041 5488 1614 1042 5489 1615 1042 5490 1615 1039 5491 1612 1036 5492 1609 1039 5493 1621 1042 5494 1626 1050 5495 1627 1050 5496 1627 1049 5497 1624 1039 5498 1621 1031 5499 1602 1032 5500 1603 1152 5501 1608 1152 5502 1608 1034 5503 1605 1031 5504 1602 1056 5505 1640 1055 5506 1639 1027 5507 1642 1027 5508 1642 1028 5509 1641 1056 5510 1640 1035 5511 1644 1153 5512 1643 1055 5513 1646 1055 5514 1646 1056 5515 1645 1035 5516 1644 1057 5517 1647 1060 5518 1650 1059 5519 1649 1059 5520 1649 1058 5521 1648 1057 5522 1647 1029 5523 1652 979 5524 1651 1020 5525 1654 1020 5526 1654 1021 5527 1653 1029 5528 1652 1014 5529 1634 1015 5530 1655 1006 5531 1656 1006 5532 1656 1054 5533 1633 1014 5534 1634 1023 5535 1657 1007 5536 1661 1044 5537 1660 1023 5538 1657 1044 5539 1660 1045 5540 1635 1023 5541 1657 1045 5542 1635 1036 5543 1636 1023 5544 1657 1036 5545 1636 1037 5546 1659 1023 5547 1657 1037 5548 1659 1022 5549 1658 1007 5550 1661 1016 5551 1663 1017 5552 1662 1017 5553 1662 1044 5554 1660 1007 5555 1661 1025 5556 1664 1061 5557 1667 1013 5558 1666 1013 5559 1666 1024 5560 1665 1025 5561 1664 1013 5562 1666 1061 5563 1667 1062 5564 1669 1062 5565 1669 1012 5566 1668 1013 5567 1666 1145 5568 1670 1012 5569 1668 1062 5570 1669 1062 5571 1669 1026 5572 1671 1145 5573 1670 1026 5574 1593 1057 5575 1673 1058 5576 1672 1058 5577 1672 1025 5578 1592 1026 5579 1593 1025 5580 1674 1058 5581 1676 1059 5582 1649 1059 5583 1649 1061 5584 1675 1025 5585 1674 1061 5586 1675 1059 5587 1649 1060 5588 1650 1060 5589 1650 1062 5590 1677 1061 5591 1675 1062 5592 1677 1060 5593 1650 1057 5594 1679 1057 5595 1679 1026 5596 1678 1062 5597 1677 1064 5598 1682 1063 5599 1681 1022 5600 1680 1022 5601 1680 1037 5602 1683 1064 5603 1682 1066 5604 1685 1065 5605 1684 1056 5606 1640 1056 5607 1640 1028 5608 1641 1066 5609 1685 1065 5610 1687 1063 5611 1686 1035 5612 1644 1035 5613 1644 1056 5614 1645 1065 5615 1687 1066 5616 1689 1067 5617 1688 1029 5618 1652 1029 5619 1652 1021 5620 1653 1066 5621 1689 1010 5622 1691 1067 5623 1690 1024 5624 1665 1024 5625 1665 1013 5626 1666 1010 5627 1691 1069 5628 1693 1068 5629 1692 1030 5630 1601 1030 5631 1601 1031 5632 1602 1069 5633 1693 1069 5634 1693 1064 5635 1682 1037 5636 1683 1037 5637 1683 1038 5638 1694 1069 5639 1693 1034 5640 1605 1035 5641 1606 1063 5642 1681 1063 5643 1681 1064 5644 1682 1034 5645 1605 1021 5646 1586 1018 5647 1583 1065 5648 1684 1065 5649 1684 1066 5650 1685 1021 5651 1586 1018 5652 1590 1022 5653 1587 1063 5654 1686 1063 5655 1686 1065 5656 1687 1018 5657 1590 1028 5658 1696 1024 5659 1695 1067 5660 1688 1067 5661 1688 1066 5662 1689 1028 5663 1696 1011 5664 1600 1029 5665 1597 1067 5666 1690 1067 5667 1690 1010 5668 1691 1011 5669 1600 1038 5670 1694 1048 5671 1697 1068 5672 1692 1068 5673 1692 1069 5674 1693 1038 5675 1694 1031 5676 1602 1034 5677 1605 1064 5678 1682 1064 5679 1682 1069 5680 1693 1031 5681 1602 978 5682 1702 1073 5683 1701 1072 5684 1700 1074 5685 1703 978 5686 1702 1072 5687 1700 1074 5688 1703 1072 5689 1700 1071 5690 1699 1070 5691 1698 1074 5692 1703 1071 5693 1699 1076 5694 1705 1075 5695 1704 1078 5696 1707 1078 5697 1707 1077 5698 1706 1076 5699 1705 1080 5700 1709 1079 5701 1708 1082 5702 1711 1082 5703 1711 1081 5704 1710 1080 5705 1709 1083 5706 1712 1079 5707 1715 1080 5708 1714 1080 5709 1714 1084 5710 1713 1083 5711 1712 1085 5712 1716 1089 5713 1721 1008 5714 1720 1008 5715 1720 1088 5716 1719 1087 5717 1718 1008 5718 1720 1087 5719 1718 1086 5720 1717 1085 5721 1716 1008 5722 1720 1086 5723 1717 1091 5724 1723 1090 5725 1722 1071 5726 1725 1071 5727 1725 1072 5728 1724 1091 5729 1723 1092 5730 1726 1009 5731 1729 1094 5732 1728 1094 5733 1728 1093 5734 1727 1092 5735 1726 1096 5736 1731 1095 5737 1730 1098 5738 1733 1098 5739 1733 1097 5740 1732 1096 5741 1731 1099 5742 1734 1102 5743 1737 1101 5744 1736 1101 5745 1736 1100 5746 1735 1099 5747 1734 1103 5748 1738 1106 5749 1741 1105 5750 1740 1105 5751 1740 1104 5752 1739 1103 5753 1738 1107 5754 1742 1110 5755 1745 1109 5756 1744 1109 5757 1744 1108 5758 1743 1107 5759 1742 1102 5760 1746 1112 5761 1749 1111 5762 1748 1111 5763 1748 1101 5764 1747 1102 5765 1746 1106 5766 1750 1114 5767 1753 1113 5768 1752 1113 5769 1752 1105 5770 1751 1106 5771 1750 1110 5772 1754 1116 5773 1757 1115 5774 1756 1115 5775 1756 1109 5776 1755 1110 5777 1754 1107 5778 1742 1078 5779 1707 1075 5780 1704 1075 5781 1704 1110 5782 1745 1107 5783 1742 1110 5784 1754 1075 5785 1759 1117 5786 1758 1117 5787 1758 1116 5788 1757 1110 5789 1754 1115 5790 1756 1114 5791 1753 1106 5792 1750 1106 5793 1750 1109 5794 1755 1115 5795 1756 1109 5796 1744 1106 5797 1741 1103 5798 1738 1103 5799 1738 1108 5800 1743 1109 5801 1744 1108 5802 1760 1103 5803 1763 1104 5804 1762 1104 5805 1762 1099 5806 1761 1108 5807 1760 1099 5808 1734 1104 5809 1739 1105 5810 1740 1105 5811 1740 1102 5812 1737 1099 5813 1734 1102 5814 1746 1105 5815 1751 1113 5816 1752 1113 5817 1752 1112 5818 1749 1102 5819 1746 1093 5820 1727 1094 5821 1728 1098 5822 1733 1098 5823 1733 1095 5824 1730 1093 5825 1727 1119 5826 1765 1118 5827 1764 1008 5828 1767 1008 5829 1767 1089 5830 1766 1119 5831 1765 1096 5832 1769 1097 5833 1768 1118 5834 1771 1118 5835 1771 1119 5836 1770 1096 5837 1769 1120 5838 1772 1123 5839 1775 1122 5840 1774 1122 5841 1774 1121 5842 1773 1120 5843 1772 1090 5844 1777 1091 5845 1776 1081 5846 1779 1081 5847 1779 1082 5848 1778 1090 5849 1777 1075 5850 1759 1076 5851 1780 1124 5852 1781 1124 5853 1781 1117 5854 1758 1075 5855 1759 1084 5856 1782 1125 5857 1786 1107 5858 1785 1084 5859 1782 1107 5860 1785 1108 5861 1760 1084 5862 1782 1108 5863 1760 1099 5864 1761 1084 5865 1782 1099 5866 1761 1100 5867 1784 1084 5868 1782 1100 5869 1784 1083 5870 1783 1125 5871 1786 1077 5872 1788 1078 5873 1787 1078 5874 1787 1107 5875 1785 1125 5876 1786 1086 5877 1789 1126 5878 1792 1074 5879 1791 1074 5880 1791 1085 5881 1790 1086 5882 1789 1074 5883 1791 1126 5884 1792 1127 5885 1794 1127 5886 1794 978 5887 1793 1074 5888 1791 1088 5889 1795 978 5890 1793 1127 5891 1794 1127 5892 1794 1087 5893 1796 1088 5894 1795 1087 5895 1718 1120 5896 1798 1121 5897 1797 1121 5898 1797 1086 5899 1717 1087 5900 1718 1086 5901 1799 1121 5902 1801 1122 5903 1774 1122 5904 1774 1126 5905 1800 1086 5906 1799 1126 5907 1800 1122 5908 1774 1123 5909 1775 1123 5910 1775 1127 5911 1802 1126 5912 1800 1127 5913 1802 1123 5914 1775 1120 5915 1804 1120 5916 1804 1087 5917 1803 1127 5918 1802 1129 5919 1807 1128 5920 1806 1083 5921 1805 1083 5922 1805 1100 5923 1808 1129 5924 1807 1131 5925 1810 1130 5926 1809 1119 5927 1765 1119 5928 1765 1089 5929 1766 1131 5930 1810 1130 5931 1812 1128 5932 1811 1096 5933 1769 1096 5934 1769 1119 5935 1770 1130 5936 1812 1131 5937 1814 1132 5938 1813 1090 5939 1777 1090 5940 1777 1082 5941 1778 1131 5942 1814 1070 5943 1816 1132 5944 1815 1085 5945 1790 1085 5946 1790 1074 5947 1791 1070 5948 1816 1134 5949 1818 1133 5950 1817 1092 5951 1726 1092 5952 1726 1093 5953 1727 1134 5954 1818 1134 5955 1818 1129 5956 1807 1100 5957 1808 1100 5958 1808 1101 5959 1819 1134 5960 1818 1095 5961 1730 1096 5962 1731 1128 5963 1806 1128 5964 1806 1129 5965 1807 1095 5966 1730 1082 5967 1711 1079 5968 1708 1130 5969 1809 1130 5970 1809 1131 5971 1810 1082 5972 1711 1079 5973 1715 1083 5974 1712 1128 5975 1811 1128 5976 1811 1130 5977 1812 1079 5978 1715 1089 5979 1821 1085 5980 1820 1132 5981 1813 1132 5982 1813 1131 5983 1814 1089 5984 1821 1071 5985 1725 1090 5986 1722 1132 5987 1815 1132 5988 1815 1070 5989 1816 1071 5990 1725 1101 5991 1819 1111 5992 1822 1133 5993 1817 1133 5994 1817 1134 5995 1818 1101 5996 1819 1093 5997 1727 1095 5998 1730 1129 5999 1807 1129 6000 1807 1134 6001 1818 1093 6002 1727 1072 6003 1827 1073 6004 1826 1012 6005 1825 1072 6006 1827 1012 6007 1825 1136 6008 1824 1137 6009 1828 1072 6010 1827 1136 6011 1824 1135 6012 1823 1137 6013 1828 1136 6014 1824 1076 6015 1832 1077 6016 1831 1139 6017 1830 1139 6018 1830 1138 6019 1829 1076 6020 1832 1080 6021 1836 1081 6022 1835 1141 6023 1834 1141 6024 1834 1140 6025 1833 1080 6026 1836 1142 6027 1837 1084 6028 1840 1080 6029 1839 1080 6030 1839 1140 6031 1838 1142 6032 1837 1146 6033 1845 1145 6034 1844 1027 6035 1843 1147 6036 1846 1146 6037 1845 1027 6038 1843 1143 6039 1841 1147 6040 1846 1027 6041 1843 1143 6042 1841 1027 6043 1843 1144 6044 1842 1091 6045 1850 1072 6046 1849 1137 6047 1848 1137 6048 1848 1148 6049 1847 1091 6050 1850 1149 6051 1851 1150 6052 1854 1032 6053 1853 1032 6054 1853 1033 6055 1852 1149 6056 1851 1154 6057 1858 1153 6058 1857 1152 6059 1856 1152 6060 1856 1151 6061 1855 1154 6062 1858 1155 6063 1859 1158 6064 1862 1157 6065 1861 1157 6066 1861 1156 6067 1860 1155 6068 1859 1159 6069 1863 1162 6070 1866 1161 6071 1865 1161 6072 1865 1160 6073 1864 1159 6074 1863 1163 6075 1867 1166 6076 1870 1165 6077 1869 1165 6078 1869 1164 6079 1868 1163 6080 1867 1156 6081 1871 1157 6082 1874 1168 6083 1873 1168 6084 1873 1167 6085 1872 1156 6086 1871 1160 6087 1875 1161 6088 1878 1170 6089 1877 1170 6090 1877 1169 6091 1876 1160 6092 1875 1164 6093 1879 1165 6094 1882 1172 6095 1881 1172 6096 1881 1171 6097 1880 1164 6098 1879 1163 6099 1867 1164 6100 1868 1138 6101 1829 1138 6102 1829 1139 6103 1830 1163 6104 1867 1164 6105 1879 1171 6106 1880 1173 6107 1884 1173 6108 1884 1138 6109 1883 1164 6110 1879 1172 6111 1881 1165 6112 1882 1160 6113 1875 1160 6114 1875 1169 6115 1876 1172 6116 1881 1165 6117 1869 1166 6118 1870 1159 6119 1863 1159 6120 1863 1160 6121 1864 1165 6122 1869 1166 6123 1885 1155 6124 1888 1162 6125 1887 1162 6126 1887 1159 6127 1886 1166 6128 1885 1155 6129 1859 1156 6130 1860 1161 6131 1865 1161 6132 1865 1162 6133 1866 1155 6134 1859 1156 6135 1871 1167 6136 1872 1170 6137 1877 1170 6138 1877 1161 6139 1878 1156 6140 1871 1150 6141 1854 1151 6142 1855 1152 6143 1856 1152 6144 1856 1032 6145 1853 1150 6146 1854 1174 6147 1892 1144 6148 1891 1027 6149 1890 1027 6150 1890 1055 6151 1889 1174 6152 1892 1154 6153 1896 1174 6154 1895 1055 6155 1894 1055 6156 1894 1153 6157 1893 1154 6158 1896 1175 6159 1897 1178 6160 1900 1177 6161 1899 1177 6162 1899 1176 6163 1898 1175 6164 1897 1148 6165 1904 1141 6166 1903 1081 6167 1902 1081 6168 1902 1091 6169 1901 1148 6170 1904 1138 6171 1883 1173 6172 1884 1124 6173 1906 1124 6174 1906 1076 6175 1905 1138 6176 1883 1084 6177 1907 1142 6178 1911 1158 6179 1910 1084 6180 1907 1158 6181 1910 1155 6182 1888 1084 6183 1907 1155 6184 1888 1166 6185 1885 1084 6186 1907 1166 6187 1885 1163 6188 1909 1084 6189 1907 1163 6190 1909 1125 6191 1908 1125 6192 1908 1163 6193 1909 1139 6194 1913 1139 6195 1913 1077 6196 1912 1125 6197 1908 1147 6198 1914 1143 6199 1917 1136 6200 1916 1136 6201 1916 1179 6202 1915 1147 6203 1914 1136 6204 1916 1012 6205 1919 1180 6206 1918 1180 6207 1918 1179 6208 1915 1136 6209 1916 1145 6210 1921 1146 6211 1920 1180 6212 1918 1180 6213 1918 1012 6214 1919 1145 6215 1921 1146 6216 1845 1147 6217 1846 1178 6218 1923 1178 6219 1923 1175 6220 1922 1146 6221 1845 1147 6222 1924 1179 6223 1926 1177 6224 1899 1177 6225 1899 1178 6226 1925 1147 6227 1924 1179 6228 1926 1180 6229 1927 1176 6230 1898 1176 6231 1898 1177 6232 1899 1179 6233 1926 1180 6234 1927 1146 6235 1929 1175 6236 1928 1175 6237 1928 1176 6238 1898 1180 6239 1927 1181 6240 1932 1158 6241 1931 1142 6242 1930 1142 6243 1930 1182 6244 1933 1181 6245 1932 1183 6246 1934 1144 6247 1891 1174 6248 1892 1174 6249 1892 1184 6250 1935 1183 6251 1934 1184 6252 1936 1174 6253 1895 1154 6254 1896 1154 6255 1896 1182 6256 1937 1184 6257 1936 1183 6258 1938 1141 6259 1903 1148 6260 1904 1148 6261 1904 1185 6262 1939 1183 6263 1938 1135 6264 1940 1136 6265 1916 1143 6266 1917 1143 6267 1917 1185 6268 1941 1135 6269 1940 1186 6270 1942 1150 6271 1854 1149 6272 1851 1149 6273 1851 1187 6274 1943 1186 6275 1942 1186 6276 1942 1157 6277 1944 1158 6278 1931 1158 6279 1931 1181 6280 1932 1186 6281 1942 1151 6282 1855 1181 6283 1932 1182 6284 1933 1182 6285 1933 1154 6286 1858 1151 6287 1855 1141 6288 1834 1183 6289 1934 1184 6290 1935 1184 6291 1935 1140 6292 1833 1141 6293 1834 1140 6294 1838 1184 6295 1936 1182 6296 1937 1182 6297 1937 1142 6298 1837 1140 6299 1838 1144 6300 1945 1183 6301 1938 1185 6302 1939 1185 6303 1939 1143 6304 1946 1144 6305 1945 1137 6306 1848 1135 6307 1940 1185 6308 1941 1185 6309 1941 1148 6310 1847 1137 6311 1848 1157 6312 1944 1186 6313 1942 1187 6314 1943 1187 6315 1943 1168 6316 1947 1157 6317 1944 1150 6318 1854 1186 6319 1942 1181 6320 1932 1181 6321 1932 1151 6322 1855 1150 6323 1854

- - - 0.01 0 0 0 0 0.01 0 0 0 0 0.01 0 0 0 0 1 - + + + 0.010000 0.000000 0.000000 0.000000 0.000000 0.010000 0.000000 -0.000000 0.000000 0.000000 0.010000 0.000000 0.000000 0.000000 0.000000 1.000000 + - - - + + + + 1.000000 + + + + + 30.000000 + + + 0.000000 + 3.333333 + + - +
diff --git a/vrx_urdf/wamv_description/urdf/cpu_cases.xacro b/vrx_urdf/wamv_description/urdf/cpu_cases.xacro index 45cd6697e..626d139f2 100644 --- a/vrx_urdf/wamv_description/urdf/cpu_cases.xacro +++ b/vrx_urdf/wamv_description/urdf/cpu_cases.xacro @@ -2,27 +2,12 @@ - - + @@ -52,29 +37,6 @@ - - - 0.073 0 -1.53 0 0 0 - - - https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases.dae - - - - 1.0 1.0 1.0 - 1.0 1.0 1.0 - - - https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases_Albedo.png - https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases_Normal.png - https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases_Roughness.png - https://fuel.gazebosim.org/1.0/openrobotics/models/cpu_cases/mesh/cpu_cases_Metalness.png - - - - - - From a667c89f7b49a590a161b69d72b96701d86a0129 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Thu, 17 Nov 2022 22:15:29 +0100 Subject: [PATCH 12/14] Restore WAMV pose. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- vrx_gz/launch/competition.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/vrx_gz/launch/competition.launch.py b/vrx_gz/launch/competition.launch.py index 6b63520e8..9d13e862e 100644 --- a/vrx_gz/launch/competition.launch.py +++ b/vrx_gz/launch/competition.launch.py @@ -39,7 +39,7 @@ def launch(context, *args, **kwargs): with open(config_file, 'r') as stream: models = Model.FromConfig(stream) else: - m = Model('wamv', 'wam-v', [-492, 186, 0, 0, 0, 1.2]) + m = Model('wamv', 'wam-v', [-532, 162, 0, 0, 0, 1]) if robot_urdf and robot_urdf != '': m.set_urdf(robot_urdf) models.append(m) From 8807931bc556f60c3b2630fc87bcc5fef838df77 Mon Sep 17 00:00:00 2001 From: M1chaelM Date: Mon, 21 Nov 2022 14:52:48 -0800 Subject: [PATCH 13/14] rename variable for clarity --- vrx_gz/src/ScanDockScoringPlugin.cc | 32 ++++++++++++------------ vrx_gz/src/ScanDockScoringPlugin.hh | 8 +++--- vrx_gz/worlds/scan_dock_deliver_task.sdf | 6 ++--- 3 files changed, 23 insertions(+), 23 deletions(-) diff --git a/vrx_gz/src/ScanDockScoringPlugin.cc b/vrx_gz/src/ScanDockScoringPlugin.cc index ac1c90a38..3649e7106 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.cc +++ b/vrx_gz/src/ScanDockScoringPlugin.cc @@ -179,7 +179,7 @@ class DockChecker /// from the "contain" plugin. /// \param[in] _minDockTime Minimum amount of seconds to stay docked to be /// considered a fully successfull dock. - /// \param[in] _dockAllowed Whether is allowed to dock in this bay or not. + /// \param[in] _correctDock Whether this is the correct bay to dock in. /// \param[in] _announceSymbol Symbol to announce via msgs. /// E.g.: red_cross, blue_circle /// \param[in] _symbolTopic Optional topic to announce the symbol. @@ -187,7 +187,7 @@ class DockChecker const std::string &_internalActivationTopic, const std::string &_exteriorActivationTopic, const std::chrono::duration _minDockTime, - const bool _dockAllowed, + const bool _correctDock, const std::string &_announceSymbol, const std::string &_symbolTopic); @@ -202,8 +202,8 @@ class DockChecker /// \return True when the robot is at the entrance or false othwerwise. public: bool AtEntrance() const; - /// \brief Whether it is allowed to dock in this bay or not. - public: bool Allowed() const; + /// \brief Whether this is the correct bay to dock in. + public: bool Correct() const; /// \brief Announce the symbol of the bay. public: void AnnounceSymbol(); @@ -237,8 +237,8 @@ class DockChecker /// \brief Current simulation time. private: std::chrono::duration simTime; - /// \brief Whether is allowed to dock in this bay or not. - private: bool dockAllowed; + /// \brief Whether this is the correct bay to dock in. + private: bool correctDock; /// \brief Timer used to calculate the elapsed time docked in the bay. private: std::chrono::duration timer; @@ -266,13 +266,13 @@ class DockChecker DockChecker::DockChecker(const std::string &_name, const std::string &_internalActivationTopic, const std::string &_externalActivationTopic, - const std::chrono::duration _minDockTime, const bool _dockAllowed, + const std::chrono::duration _minDockTime, const bool _correctDock, const std::string &_announceSymbol, const std::string &_symbolTopic) : name(_name), internalActivationTopic(_internalActivationTopic), externalActivationTopic(_externalActivationTopic), minDockTime(_minDockTime), - dockAllowed(_dockAllowed), + correctDock(_correctDock), symbolTopic(_symbolTopic) { // Override the docks own sdf parameters @@ -317,9 +317,9 @@ bool DockChecker::AtEntrance() const } ///////////////////////////////////////////////// -bool DockChecker::Allowed() const +bool DockChecker::Correct() const { - return this->dockAllowed; + return this->correctDock; } ///////////////////////////////////////////////// @@ -577,13 +577,13 @@ bool ScanDockScoringPlugin::Implementation::ParseSDF(sdf::ElementPtr _sdf) } double minDockTime = bayElem->Get("min_dock_time"); - // Required: dock allowed. - if (!bayElem->GetElement("dock_allowed")) + // Required: correct dock . + if (!bayElem->GetElement("correct_dock")) { - gzerr << " missing" << std::endl; + gzerr << " missing" << std::endl; return false; } - bool dockAllowed = bayElem->Get("dock_allowed"); + bool correctDock = bayElem->Get("correct_dock"); std::string announceSymbol = ""; if (!bayElem->HasElement("symbol")) @@ -596,7 +596,7 @@ bool ScanDockScoringPlugin::Implementation::ParseSDF(sdf::ElementPtr _sdf) std::unique_ptr dockChecker( new DockChecker(bayName, internalActivationTopic, externalActivationTopic, std::chrono::duration(minDockTime), - dockAllowed, announceSymbol, symbolTopic)); + correctDock, announceSymbol, symbolTopic)); // Add the dock checker. this->dockCheckers.push_back(std::move(dockChecker)); @@ -698,7 +698,7 @@ void ScanDockScoringPlugin::PreUpdate(const sim::UpdateInfo &_info, } // Is this the right bay? - if (dockChecker->Allowed()) + if (dockChecker->Correct()) { this->SetScore(this->Score() + this->dataPtr->correctDockBonusPoints); if (this->TaskState() == "running") diff --git a/vrx_gz/src/ScanDockScoringPlugin.hh b/vrx_gz/src/ScanDockScoringPlugin.hh index a7cb287c6..2ee948b65 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.hh +++ b/vrx_gz/src/ScanDockScoringPlugin.hh @@ -52,7 +52,7 @@ namespace vrx /// notifications from the external activation zone. /// : Minimum amount of seconds to stay docked to be /// considered a fully successfull dock. - /// : Whether is allowed to dock in this bay or not. + /// : True if this is the correct bay to dock in. /// : Required string with format _, where /// color can be "red", "green", "blue", "yellow" and shape can be /// "triangle", "circle", "cross", "rectangle". If this parameter is @@ -89,7 +89,7 @@ namespace vrx /// /vrx/dock_2022/bay_1_external/contain /// /vrx/dock_2022_placard1/symbol /// 10.0 - /// False + /// False /// red_rectangle /// /// @@ -98,7 +98,7 @@ namespace vrx /// /vrx/dock_2022/bay_2_external/contain /// /vrx/dock_2022_placard2/symbol /// 10.0 - /// True + /// True /// blue_triangle /// /// @@ -107,7 +107,7 @@ namespace vrx /// /vrx/dock_2022/bay_3_external/contain /// /vrx/dock_2022_placard3/symbol /// 10.0 - /// False + /// False /// yellow_circle /// /// diff --git a/vrx_gz/worlds/scan_dock_deliver_task.sdf b/vrx_gz/worlds/scan_dock_deliver_task.sdf index 5c82e21c6..c0317449d 100644 --- a/vrx_gz/worlds/scan_dock_deliver_task.sdf +++ b/vrx_gz/worlds/scan_dock_deliver_task.sdf @@ -560,7 +560,7 @@ /vrx/dock_2022/bay_1_external/contain /vrx/dock_2022_placard1/symbol 10.0 - False + False red_rectangle @@ -569,7 +569,7 @@ /vrx/dock_2022/bay_2_external/contain /vrx/dock_2022_placard2/symbol 10.0 - True + True blue_triangle @@ -578,7 +578,7 @@ /vrx/dock_2022/bay_3_external/contain /vrx/dock_2022_placard3/symbol 10.0 - False + False yellow_circle From 2581ad4ea4bc0d2255ce1d4ce78ea79324273930 Mon Sep 17 00:00:00 2001 From: M1chaelM Date: Mon, 21 Nov 2022 15:28:06 -0800 Subject: [PATCH 14/14] documentation tweak --- vrx_gz/src/ScanDockScoringPlugin.hh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/vrx_gz/src/ScanDockScoringPlugin.hh b/vrx_gz/src/ScanDockScoringPlugin.hh index 2ee948b65..c481a525c 100644 --- a/vrx_gz/src/ScanDockScoringPlugin.hh +++ b/vrx_gz/src/ScanDockScoringPlugin.hh @@ -60,9 +60,9 @@ namespace vrx /// The vehicle should dock in the bay matching this color and shape. /// Topic to publish the symbol announcement. /// : Points granted when the vehicle successfully - /// dock-and-undock in any bay. Default value is 10. + /// docks and undocks in any bay. Default value is 10. /// : Points granted when the vehicle successfully - /// dock-and-undock in the specified bay. Default value is 10. + /// docks and undocks in the specified bay. Default value is 10. /// Here's an example: ///