diff --git a/.gitignore b/.gitignore index 259148f..f4f6338 100644 --- a/.gitignore +++ b/.gitignore @@ -30,3 +30,7 @@ *.exe *.out *.app + +.idea +build +cmake-build-debug diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..994c43c --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,5 @@ +cmake_minimum_required(VERSION 3.18) +project(RGLGazeboPlugin) + +add_subdirectory(RGLServerPlugin) +add_subdirectory(RGLGuiPlugin) \ No newline at end of file diff --git a/README.md b/README.md index 89de190..8c052e2 100644 --- a/README.md +++ b/README.md @@ -1 +1,25 @@ -# RGLGazeboPlugin \ No newline at end of file +# RGLGazeboPlugin +## Warning: + +Currently tested only on ubuntu 20.04 (ubuntu 22 has faulty gazebo fortress atm) + +### Installation: +From RGLGazeboPlugin directory: +``` +mkdir build +cd build +cmake .. +make -j +cd .. +export IGN_GAZEBO_SYSTEM_PLUGIN_PATH=`pwd`/build/RGLServerPlugin +export IGN_GUI_PLUGIN_PATH=`pwd`/build/RGLGuiPlugin +``` +### demo: +``` +cd test_world +ign gazebo -v 4 actor_world.sdf +``` + +1. load RGLGuiPlugin from the menu on the upper right +2. press the refresh button in the plugin +3. start the simulation by pressing play, the lidar hits should be visible in the GUI \ No newline at end of file diff --git a/RGLGuiPlugin/CMakeLists.txt b/RGLGuiPlugin/CMakeLists.txt new file mode 100644 index 0000000..b7c50c8 --- /dev/null +++ b/RGLGuiPlugin/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) + +if(POLICY CMP0100) + cmake_policy(SET CMP0100 NEW) +endif() + +project(RGLGuiPlugin) + +find_package(ignition-rendering6 REQUIRED) + +# GUI plugin +set(GUI_PLUGIN RGLGuiPlugin) + +set(CMAKE_AUTOMOC ON) + +find_package(ignition-gui6 REQUIRED) +find_package(ignition-msgs8 REQUIRED) + +QT5_ADD_RESOURCES(resources_RCC ${GUI_PLUGIN}.qrc) + +add_library(${GUI_PLUGIN} SHARED + ${GUI_PLUGIN}.cc + ${resources_RCC} + ) +target_link_libraries(${GUI_PLUGIN} + PRIVATE + ignition-gui6::ignition-gui6 + ignition-rendering6::ignition-rendering6 + ignition-msgs8::ignition-msgs8 + ) \ No newline at end of file diff --git a/RGLGuiPlugin/RGLGuiPlugin.cc b/RGLGuiPlugin/RGLGuiPlugin.cc new file mode 100644 index 0000000..843d65d --- /dev/null +++ b/RGLGuiPlugin/RGLGuiPlugin.cc @@ -0,0 +1,454 @@ +/* + * Copyright (C) 2022 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 +#include +#include +#include + +#include "RGLGuiPlugin.hh" + +using namespace std::literals::chrono_literals; + +/// \brief Private data class for RGLGuiPlugin +class ignition::gui::plugins::RGLGuiPluginPrivate +{ + /// \brief Makes a request to populate the scene with markers + public: void PublishMarkers(); + + /// \brief Makes a request to delete all markers related to the point cloud. + public: void ClearMarkers(); + + /// \brief Transport node + public: ignition::transport::Node node; + + /// \brief Name of topic for PointCloudPacked + public: std::string pointCloudTopic; + + /// \brief List of topics publishing PointCloudPacked. + public: QStringList pointCloudTopicList; + + /// \brief Protect variables changed from transport and the user + public: std::recursive_mutex mutex; + + /// \brief Point cloud message containing XYZ positions + public: ignition::msgs::PointCloudPacked pointCloudMsg; + + /// \brief Color for minimum value, changeable at runtime +public: ignition::math::Color minColor{ignition::math::Color::Red}; + + /// \brief Size of each point, changeable at runtime + public: float pointSize{1}; + + /// \brief True if showing, changeable at runtime + public: bool showing{true}; + + /// \brief Marks when a new change has been requested. + public: bool dirty{false}; + + public: ignition::rendering::MarkerPtr marker = nullptr; +}; + +using namespace ignition::gui::plugins; + +///////////////////////////////////////////////// +RGLGuiPlugin::RGLGuiPlugin() + : ignition::gui::Plugin(), + dataPtr(std::make_unique()) {} + +///////////////////////////////////////////////// +RGLGuiPlugin::~RGLGuiPlugin() +{ + this->dataPtr->ClearMarkers(); +} + +///////////////////////////////////////////////// +void RGLGuiPlugin::LoadConfig(const tinyxml2::XMLElement *_pluginElem) +{ + if (this->title.empty()) + this->title = "RGL Visualize"; + + // Parameters from XML + if (_pluginElem) + { + auto pointCloudTopicElem = + _pluginElem->FirstChildElement("point_cloud_topic"); + if (nullptr != pointCloudTopicElem && + nullptr != pointCloudTopicElem->GetText()) + { + this->SetPointCloudTopicList({pointCloudTopicElem->GetText()}); + this->OnPointCloudTopic(this->dataPtr->pointCloudTopicList.at(0)); + } + } + + ignition::gui::App()->findChild< + ignition::gui::MainWindow *>()->installEventFilter(this); +} + +////////////////////////////////////////////////// +void RGLGuiPlugin::OnPointCloudTopic(const QString &_pointCloudTopic) +{ + std::lock_guard lock(this->dataPtr->mutex); + // Unsubscribe from previous choice + if (!this->dataPtr->pointCloudTopic.empty() && + !this->dataPtr->node.Unsubscribe(this->dataPtr->pointCloudTopic)) + { + ignerr << "Unable to unsubscribe from topic [" + << this->dataPtr->pointCloudTopic <<"]" <dataPtr->ClearMarkers(); + + this->dataPtr->pointCloudTopic = _pointCloudTopic.toStdString(); + + // Request service + this->dataPtr->node.Request(this->dataPtr->pointCloudTopic, + &RGLGuiPlugin::OnPointCloudService, this); + + // Create new subscription + if (!this->dataPtr->node.Subscribe(this->dataPtr->pointCloudTopic, + &RGLGuiPlugin::OnPointCloud, this)) + { + ignerr << "Unable to subscribe to topic [" + << this->dataPtr->pointCloudTopic << "]\n"; + return; + } + ignmsg << "Subscribed to " << this->dataPtr->pointCloudTopic << std::endl; +} + +////////////////////////////////////////////////// +void RGLGuiPlugin::Show(bool _show) +{ + this->dataPtr->showing = _show; + if (_show) + { + this->dataPtr->PublishMarkers(); + } + else + { + this->dataPtr->ClearMarkers(); + } +} + +///////////////////////////////////////////////// +void RGLGuiPlugin::OnRefresh() +{ + std::lock_guard lock(this->dataPtr->mutex); + ignmsg << "Refreshing topic list for point cloud messages." << std::endl; + + // Clear + this->dataPtr->pointCloudTopicList.clear(); + + // Get updated list + std::vector allTopics; + this->dataPtr->node.TopicList(allTopics); + for (const auto& topic : allTopics) + { + std::vector publishers; + this->dataPtr->node.TopicInfo(topic, publishers); + for (const auto& pub : publishers) + { + if (pub.MsgTypeName() == "ignition.msgs.PointCloudPacked") + { + this->dataPtr->pointCloudTopicList.push_back( + QString::fromStdString(topic)); + } + } + } + + if (!this->dataPtr->pointCloudTopicList.empty()) + { + this->OnPointCloudTopic(this->dataPtr->pointCloudTopicList.at(0)); + } + + this->PointCloudTopicListChanged(); + this->FloatVTopicListChanged(); +} + +///////////////////////////////////////////////// +QStringList RGLGuiPlugin::PointCloudTopicList() const +{ + return this->dataPtr->pointCloudTopicList; +} + +///////////////////////////////////////////////// +void RGLGuiPlugin::SetPointCloudTopicList( + const QStringList &_pointCloudTopicList) +{ + this->dataPtr->pointCloudTopicList = _pointCloudTopicList; + this->PointCloudTopicListChanged(); +} + +////////////////////////////////////////////////// +void RGLGuiPlugin::OnPointCloud( + const ignition::msgs::PointCloudPacked &_msg) +{ + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->pointCloudMsg = _msg; + this->dataPtr->PublishMarkers(); +} + +////////////////////////////////////////////////// +void RGLGuiPlugin::OnPointCloudService( + const ignition::msgs::PointCloudPacked &_msg, bool _result) +{ + if (!_result) + { + ignerr << "Service request failed." << std::endl; + return; + } + this->OnPointCloud(_msg); +} + +////////////////////////////////////////////////// +void RGLGuiPluginPrivate::PublishMarkers() +{ + IGN_PROFILE("RGLGuiPlugin::PublishMarkers"); + + if (!this->showing) + return; + + this->dirty = true; +} + +////////////////////////////////////////////////// +void RGLGuiPluginPrivate::ClearMarkers() +{ + if (this->pointCloudTopic.empty() || marker == nullptr) + return; + + marker->ClearPoints(); +} + +///////////////////////////////////////////////// +QColor RGLGuiPlugin::MinColor() const +{ + return ignition::gui::convert(this->dataPtr->minColor); +} + +///////////////////////////////////////////////// +void RGLGuiPlugin::SetMinColor(const QColor &_minColor) +{ + this->dataPtr->minColor = ignition::gui::convert(_minColor); + this->MinColorChanged(); + this->dataPtr->PublishMarkers(); +} + +///////////////////////////////////////////////// +float RGLGuiPlugin::PointSize() const +{ + return this->dataPtr->pointSize; +} + +///////////////////////////////////////////////// +//! [eventFilter] +bool RGLGuiPlugin::eventFilter(QObject *_obj, QEvent *_event) +{ + if (_event->type() == ignition::gui::events::Render::kType) + { + // This event is called in the render thread, so it's safe to make + // rendering calls here + this->PerformRenderingOperations(); + } + + // Standard event processing + return QObject::eventFilter(_obj, _event); +} +//! [eventFilter] + +///////////////////////////////////////////////// +void RGLGuiPlugin::SetPointSize(float _pointSize) +{ + this->dataPtr->pointSize = _pointSize; + this->PointSizeChanged(); + this->dataPtr->PublishMarkers(); +} + +///////////////////////////////////////////////// +//! [performRenderingOperations] +void RGLGuiPlugin::PerformRenderingOperations() +{ + if (!this->dataPtr->dirty) + { + return; + } + + if (nullptr == this->scene) + { + this->FindScene(); + } + + if (nullptr == this->scene) return; + + if (nullptr == this->dataPtr->marker) { + this->CreateMarker(); + } + + if (nullptr == this->dataPtr->marker) return; + + this->dataPtr->marker->ClearPoints(); + + this->dataPtr->marker->SetSize(this->dataPtr->pointSize); + + ignition::rendering::MaterialPtr materialPtr = this->scene->CreateMaterial(); + materialPtr->SetLightingEnabled(false); + materialPtr->SetDiffuse(this->dataPtr->minColor); + dataPtr->marker->SetMaterial(materialPtr, true); + this->scene->DestroyMaterial(materialPtr); + + ignition::msgs::PointCloudPackedIterator + iterX(this->dataPtr->pointCloudMsg, "x"); + ignition::msgs::PointCloudPackedIterator + iterY(this->dataPtr->pointCloudMsg, "y"); + ignition::msgs::PointCloudPackedIterator + iterZ(this->dataPtr->pointCloudMsg, "z"); + + + auto start_populating_msg = std::chrono::system_clock::now(); + + for (; iterX != iterX.End(); ++iterX, ++iterY, ++iterZ) + { + // setting the color here doesn't work + dataPtr->marker->AddPoint(*iterX, *iterY, *iterZ, ignition::math::Color::Red); + } + + auto end_populating_msg = std::chrono::system_clock::now(); + auto time_to_populate_msg = std::chrono::duration_cast(end_populating_msg - start_populating_msg); + ignmsg << "GUI populate message and visualize time: " << time_to_populate_msg.count() << " ms\n"; + + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->dirty = false; +} +//! [performRenderingOperations] + +void RGLGuiPlugin::CreateMarker() { + if (nullptr == this->scene) { + ignerr << "RGLGuiPlugin could not find scene while attempting to create marker"; + return; + } + + static size_t rgl_id = 0; + // Create the name for the marker + std::string name = "__RGL_MARKER_VISUAL__" + std::to_string(rgl_id); + + rgl_id++; + + // Create the new marker + visualPtr = this->scene->CreateVisual(name); + + // Create and load the marker + this->dataPtr->marker = this->scene->CreateMarker(); + + // Set the marker values from the Marker Message + dataPtr->marker->SetLayer(0); + + dataPtr->marker->SetLifetime(10min); + + dataPtr->marker->SetSize(this->dataPtr->pointSize); + + dataPtr->marker->SetType(ignition::rendering::MarkerType::MT_POINTS); + + ignition::rendering::MaterialPtr materialPtr = this->scene->CreateMaterial(); + materialPtr->SetLightingEnabled(false); + materialPtr->SetDiffuse(this->dataPtr->minColor); + dataPtr->marker->SetMaterial(materialPtr, true); + this->scene->DestroyMaterial(materialPtr); + + // Add populated marker to the visual + visualPtr->AddGeometry(dataPtr->marker); + + this->scene->RootVisual()->AddChild(visualPtr); +} + +///////////////////////////////////////////////// +void RGLGuiPlugin::FindScene() +{ + auto loadedEngNames = ignition::rendering::loadedEngines(); + if (loadedEngNames.empty()) + { + igndbg << "No rendering engine is loaded yet" << std::endl; + return; + } + + // assume there is only one engine loaded + auto engineName = loadedEngNames[0]; + if (loadedEngNames.size() > 1) + { + igndbg << "More than one engine is available. " + << "Using engine [" << engineName << "]" << std::endl; + } + auto engine = ignition::rendering::engine(engineName); + if (!engine) + { + ignerr << "Internal error: failed to load engine [" << engineName + << "]. Grid plugin won't work." << std::endl; + return; + } + + if (engine->SceneCount() == 0) + { + igndbg << "No scene has been created yet" << std::endl; + return; + } + + // Get first scene + auto scenePtr = engine->SceneByIndex(0); + if (nullptr == scenePtr) + { + ignerr << "Internal error: scene is null." << std::endl; + return; + } + + if (engine->SceneCount() > 1) + { + igndbg << "More than one scene is available. " + << "Using scene [" << scene->Name() << "]" << std::endl; + } + + if (!scenePtr->IsInitialized() || nullptr == scenePtr->RootVisual()) + { + return; + } + + this->scene = scenePtr; +} + +// Register this plugin +IGNITION_ADD_PLUGIN(RGLGuiPlugin, + ignition::gui::Plugin) diff --git a/RGLGuiPlugin/RGLGuiPlugin.hh b/RGLGuiPlugin/RGLGuiPlugin.hh new file mode 100644 index 0000000..46e61a6 --- /dev/null +++ b/RGLGuiPlugin/RGLGuiPlugin.hh @@ -0,0 +1,264 @@ +/* + * Copyright (C) 2022 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 GZ_GUI_PLUGINS_POINTCLOUD_HH_ +#define GZ_GUI_PLUGINS_POINTCLOUD_HH_ + +#include + +#ifdef _MSC_VER +#pragma warning(push, 0) +#endif +#include +#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +#include +#include + +namespace ignition::gui::plugins +{ + class RGLGuiPluginPrivate; + + /// \brief Visualize `gz::msgs::PointCloudPacked` messages in a 3D + /// scene. + /// + /// By default, the whole cloud is displayed using a single color. Users + /// can optionally choose a topic publishing `gz::msgs::FloatV` messages + /// which will be used to color all points with a color gradient according to + /// their values. The float message must have the same number of elements as + /// the point cloud and be indexed the same way. NaN values on the FloatV + /// message aren't displayed. + /// + /// Requirements: + /// * A plugin that loads a 3D scene, such as `MinimalScene` + /// * The `MarkerManager` plugin + /// + /// Parameters: + /// + /// * ``: Topic to receive + /// `gz::msgs::PointCloudPacked` messages. + /// * ``: Topic to receive `gz::msgs::FloatV` messages. + class RGLGuiPlugin : public ignition::gui::Plugin + { + Q_OBJECT + + /// \brief List of topics publishing PointCloudPacked messages + Q_PROPERTY( + QStringList pointCloudTopicList + READ PointCloudTopicList + WRITE SetPointCloudTopicList + NOTIFY PointCloudTopicListChanged + ) + + /// \brief List of topics publishing FloatV messages + Q_PROPERTY( + QStringList floatVTopicList + READ FloatVTopicList + WRITE SetFloatVTopicList + NOTIFY FloatVTopicListChanged + ) + + /// \brief Color for minimum value + Q_PROPERTY( + QColor minColor + READ MinColor + WRITE SetMinColor + NOTIFY MinColorChanged + ) + + /// \brief Color for maximum value + Q_PROPERTY( + QColor maxColor + READ MaxColor + WRITE SetMaxColor + NOTIFY MaxColorChanged + ) + + /// \brief Minimum value + Q_PROPERTY( + float minFloatV + READ MinFloatV + WRITE SetMinFloatV + NOTIFY MinFloatVChanged + ) + + /// \brief Maximum value + Q_PROPERTY( + float maxFloatV + READ MaxFloatV + WRITE SetMaxFloatV + NOTIFY MaxFloatVChanged + ) + + /// \brief Point size + Q_PROPERTY( + float pointSize + READ PointSize + WRITE SetPointSize + NOTIFY PointSizeChanged + ) + + /// \brief Constructor + public: RGLGuiPlugin(); + + /// \brief Destructor + public: ~RGLGuiPlugin() override; + + // Documentation inherited + public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; + + /// \brief Callback function for point cloud topic. + /// \param[in] _msg Point cloud message + public: void OnPointCloud(const msgs::PointCloudPacked &_msg); + + /// \brief Callback function for point cloud service + /// \param[in] _msg Point cloud message + /// \param[out] _result True on success. + public: void OnPointCloudService(const msgs::PointCloudPacked &_msg, + bool _result); + + /// \brief Get the topic list + /// \return List of topics + public: Q_INVOKABLE QStringList PointCloudTopicList() const; + + /// \brief Set the topic list from a string + /// \param[in] _pointCloudTopicList List of topics. + public: Q_INVOKABLE void SetPointCloudTopicList( + const QStringList &_pointCloudTopicList); + + /// \brief Notify that topic list has changed + signals: void PointCloudTopicListChanged(); + + /// \brief Set topic to subscribe to for point cloud. + /// \param[in] _topicName Name of selected topic + public: Q_INVOKABLE void OnPointCloudTopic(const QString &_topicName); + + /// \brief Callback function for float vector topic. + /// \param[in] _msg Float vector message + public: void OnFloatV(const msgs::Float_V &_msg); + + /// \brief Callback function for point cloud service + /// \param[in] _msg Float vector message + /// \param[out] _result True on success. + public: void OnFloatVService(const msgs::Float_V &_msg, bool _result); + + /// \brief Get the topic list + /// \return List of topics + public: Q_INVOKABLE QStringList FloatVTopicList() const; + + /// \brief Set the topic list from a string + /// \param[in] _floatVTopicList List of topics. + public: Q_INVOKABLE void SetFloatVTopicList( + const QStringList &_floatVTopicList); + + /// \brief Notify that topic list has changed + signals: void FloatVTopicListChanged(); + + /// \brief Set topic to subscribe to for float vectors. + /// \param[in] _topicName Name of selected topic + public: Q_INVOKABLE void OnFloatVTopic(const QString &_topicName); + + /// \brief Get the minimum color + /// \return Minimum color + public: Q_INVOKABLE QColor MinColor() const; + + /// \brief Set the minimum color + /// \param[in] _minColor Minimum color. + public: Q_INVOKABLE void SetMinColor(const QColor &_minColor); + + /// \brief Notify that minimum color has changed + signals: void MinColorChanged(); + + /// \brief Get the maximum color + /// \return Maximum color + public: Q_INVOKABLE QColor MaxColor() const; + + /// \brief Set the maximum color + /// \param[in] _maxColor Maximum color. + public: Q_INVOKABLE void SetMaxColor(const QColor &_maxColor); + + /// \brief Notify that maximum color has changed + signals: void MaxColorChanged(); + + /// \brief Get the minimum value + /// \return Minimum value + public: Q_INVOKABLE float MinFloatV() const; + + /// \brief Set the minimum value + /// \param[in] _minFloatV Minimum value. + public: Q_INVOKABLE void SetMinFloatV(float _minFloatV); + + /// \brief Notify that minimum value has changed + signals: void MinFloatVChanged(); + + /// \brief Get the maximum value + /// \return Maximum value + public: Q_INVOKABLE float MaxFloatV() const; + + /// \brief Set the maximum value + /// \param[in] _maxFloatV Maximum value. + public: Q_INVOKABLE void SetMaxFloatV(float _maxFloatV); + + /// \brief Notify that maximum value has changed + signals: void MaxFloatVChanged(); + + /// \brief Get the point size + /// \return Maximum value + public: Q_INVOKABLE float PointSize() const; + + /// \brief Set the point size + /// \param[in] _pointSize Maximum value. + public: Q_INVOKABLE void SetPointSize(float _pointSize); + + /// \brief Notify that point size has changed + signals: void PointSizeChanged(); + + /// \brief Set whether to show the point cloud. + /// \param[in] _show Boolean value for displaying the points. + public: Q_INVOKABLE void Show(bool _show); + + /// \brief Callback when refresh button is pressed. + public: Q_INVOKABLE void OnRefresh(); + + /// \internal + /// \brief Pointer to private data + private: std::unique_ptr dataPtr; + + /// \brief All rendering operations must happen within this call + private: void PerformRenderingOperations(); + + /// \brief Encapsulates the logic to find the rendering scene through the + /// render engine singleton. + private: void FindScene(); + + /// \brief Callback for all installed event filters. + /// \param[in] _obj Object that received the event + /// \param[in] _event Event + private: bool eventFilter(QObject *_obj, QEvent *_event) override; + + /// \brief Pointer to the rendering scene. + private: ignition::rendering::ScenePtr scene{nullptr}; + + private: ignition::rendering::VisualPtr visualPtr = nullptr; + + private: void CreateMarker(); + }; +} +#endif diff --git a/RGLGuiPlugin/RGLGuiPlugin.qml b/RGLGuiPlugin/RGLGuiPlugin.qml new file mode 100644 index 0000000..07387b7 --- /dev/null +++ b/RGLGuiPlugin/RGLGuiPlugin.qml @@ -0,0 +1,151 @@ +/* + * Copyright (C) 2022 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. + * + */ + +import QtQuick 2.9 +import QtQuick.Controls 2.1 +import QtQuick.Dialogs 1.0 +import QtQuick.Controls.Material 2.1 +import QtQuick.Layouts 1.3 +import ignition.gui 1.0 +import "qrc:/qml" + +ColumnLayout { + spacing: 10 + Layout.minimumWidth: 350 + Layout.minimumHeight: 350 + anchors.fill: parent + anchors.leftMargin: 10 + anchors.rightMargin: 10 + + RowLayout { + spacing: 10 + Layout.fillWidth: true + + Switch { + Layout.alignment: Qt.AlignHCenter + id: displayVisual + Layout.columnSpan: 5 + Layout.fillWidth: true + text: qsTr("Show") + checked: true + onToggled: { + RGLGuiPlugin.Show(checked) + } + } + + RoundButton { + Layout.columnSpan: 1 + text: "\u21bb" + Material.background: Material.primary + onClicked: { + RGLGuiPlugin.OnRefresh(); + pcCombo.currentIndex = 0 + } + ToolTip.visible: hovered + ToolTip.delay: Qt.styleHints.mousePressAndHoldInterval + ToolTip.text: qsTr("Refresh list of topics publishing point clouds and float vectors") + } + } + + GridLayout { + columns: 3 + columnSpacing: 10 + Layout.fillWidth: true + + Label { + Layout.columnSpan: 1 + text: "Point cloud" + } + + ComboBox { + Layout.columnSpan: 2 + id: pcCombo + Layout.fillWidth: true + model: RGLGuiPlugin.pointCloudTopicList + currentIndex: 0 + onCurrentIndexChanged: { + if (currentIndex < 0) + return; + RGLGuiPlugin.OnPointCloudTopic(textAt(currentIndex)); + } + ToolTip.visible: hovered + ToolTip.delay: Qt.styleHints.mousePressAndHoldInterval + ToolTip.text: qsTr("Gazebo Transport topics publishing PointCloudPacked messages") + } + + Label { + Layout.columnSpan: 1 + text: "Point size" + } + + IgnSpinBox { + id: pointSizeSpin + value: RGLGuiPlugin.pointSize + minimumValue: 1 + maximumValue: 1000 + decimals: 0 + onEditingFinished: { + RGLGuiPlugin.SetPointSize(pointSizeSpin.value) + } + } + } + + RowLayout { + spacing: 10 + Layout.fillWidth: true + + Label { + Layout.columnSpan: 1 + text: "Color" + } + + Button { + Layout.columnSpan: 1 + id: minColorButton + ToolTip.visible: hovered + ToolTip.delay: Qt.styleHints.mousePressAndHoldInterval + ToolTip.text: qsTr("Color for minimum value") + onClicked: minColorDialog.open() + background: Rectangle { + implicitWidth: 40 + implicitHeight: 40 + radius: 5 + border.color: RGLGuiPlugin.minColor + border.width: 2 + color: RGLGuiPlugin.minColor + } + ColorDialog { + id: minColorDialog + title: "Choose a color for the minimum value" + visible: false + onAccepted: { + RGLGuiPlugin.SetMinColor(minColorDialog.color) + minColorDialog.close() + } + onRejected: { + minColorDialog.close() + } + } + } + } + + Item { + Layout.columnSpan: 6 + width: 10 + Layout.fillHeight: true + } +} diff --git a/RGLGuiPlugin/RGLGuiPlugin.qrc b/RGLGuiPlugin/RGLGuiPlugin.qrc new file mode 100644 index 0000000..a7fb03c --- /dev/null +++ b/RGLGuiPlugin/RGLGuiPlugin.qrc @@ -0,0 +1,5 @@ + + + RGLGuiPlugin.qml + + diff --git a/RGLServerPlugin/CMakeLists.txt b/RGLServerPlugin/CMakeLists.txt new file mode 100644 index 0000000..9c6c0b6 --- /dev/null +++ b/RGLServerPlugin/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.18) +project(RGLServerPlugin) +set(CMAKE_CXX_STANDARD 20) + +find_package(ignition-gazebo6 REQUIRED) +find_package(ignition-plugin1 REQUIRED) + +# External dependencies +add_subdirectory(external) + +include_directories(include) + +add_library(RGLServerPluginManager SHARED src/RGLServerPluginManager.cc src/Mesh.cc src/Utils.cc src/Scene.cc) +target_link_libraries(RGLServerPluginManager + ignition-gazebo6::ignition-gazebo6 + ignition-plugin1::ignition-plugin1 + RobotecGPULidar +) + +add_library(RGLServerPluginInstance SHARED src/RGLServerPluginInstance.cc src/Lidar.cc src/Utils.cc) +target_link_libraries(RGLServerPluginInstance + ignition-gazebo6::ignition-gazebo6 + ignition-plugin1::ignition-plugin1 + RobotecGPULidar +) diff --git a/RGLServerPlugin/external/CMakeLists.txt b/RGLServerPlugin/external/CMakeLists.txt new file mode 100644 index 0000000..17cd44c --- /dev/null +++ b/RGLServerPlugin/external/CMakeLists.txt @@ -0,0 +1,9 @@ +include(FetchContent) + +FetchContent_Declare( + RobotecGPULidar + GIT_REPOSITORY git@github.com:RobotecAI/RobotecGPULidar.git + GIT_TAG v0.10.2 +) + +FetchContent_MakeAvailable(RobotecGPULidar) \ No newline at end of file diff --git a/RGLServerPlugin/include/RGLServerPluginInstance.hh b/RGLServerPlugin/include/RGLServerPluginInstance.hh new file mode 100644 index 0000000..cccc482 --- /dev/null +++ b/RGLServerPlugin/include/RGLServerPluginInstance.hh @@ -0,0 +1,92 @@ +#pragma once + +#include "rgl/api/experimental.h" + +#include + +#include +#include +#include + +#include + +#define WORLD_ENTITY_ID 1 + +#define RGL_CHECK(call) \ +do { \ + rgl_status_t status = call; \ + if (status != RGL_SUCCESS) { \ + const char* msg; \ + rgl_get_last_error_string(&msg); \ + ignerr << msg; \ + exit(1); \ + } \ +} while(0) + +using namespace std::literals::chrono_literals; + +namespace rgl { + class RGLServerPluginInstance : + public ignition::gazebo::System, + public ignition::gazebo::ISystemConfigure, + public ignition::gazebo::ISystemPreUpdate, + public ignition::gazebo::ISystemPostUpdate { + + public: + RGLServerPluginInstance(); + + ~RGLServerPluginInstance() override; + + // only called once, when plugin is being loaded + void Configure( + const ignition::gazebo::Entity& entity, + const std::shared_ptr& sdf, + ignition::gazebo::EntityComponentManager& ecm, + ignition::gazebo::EventManager& eventMgr) override; + + // called every time before physics update runs (can change entities) + void PreUpdate( + const ignition::gazebo::UpdateInfo& info, + ignition::gazebo::EntityComponentManager& ecm) override; + + // called every time after physics runs (can't change entities) + void PostUpdate( + const ignition::gazebo::UpdateInfo& info, + const ignition::gazebo::EntityComponentManager& ecm) override; + + private: + ////////////////////////////////////////////// Variables ///////////////////////////////////////////// + + size_t current_update = 0; + + size_t updates_between_raytraces = 0; + + size_t last_raytrace_update = 0; + + ignition::transport::Node::Publisher pointcloud_publisher; + + ignition::transport::Node node; + + ignition::gazebo::Entity gazebo_lidar = 0; + + int lidar_id = -1; + + bool lidar_exists = true; + + rgl_lidar_t rgl_lidar = nullptr; + + std::chrono::steady_clock::duration last_raytrace_time = 0ms; + + std::chrono::steady_clock::duration time_between_raytraces = 100ms; + + ////////////////////////////////////////////// Functions ///////////////////////////////////////////// + + void CreateLidar(ignition::gazebo::Entity entity); + + void UpdateLidarPose(const ignition::gazebo::EntityComponentManager& ecm); + + void RayTrace(ignition::gazebo::EntityComponentManager& ecm, std::chrono::steady_clock::duration sim_time, bool paused); + + bool CheckLidarExists(ignition::gazebo::Entity entity); + }; +} diff --git a/RGLServerPlugin/include/RGLServerPluginManager.hh b/RGLServerPlugin/include/RGLServerPluginManager.hh new file mode 100644 index 0000000..b32dded --- /dev/null +++ b/RGLServerPlugin/include/RGLServerPluginManager.hh @@ -0,0 +1,162 @@ +#pragma once + +#include "rgl/api/experimental.h" + +#include + +#include +#include +#include + +#include + +#define WORLD_ENTITY_ID 1 + +#define RGL_CHECK(call) \ +do { \ + rgl_status_t status = call; \ + if (status != RGL_SUCCESS) { \ + const char* msg; \ + rgl_get_last_error_string(&msg); \ + ignerr << msg; \ + exit(1); \ + } \ +} while(0) + +namespace rgl { + class RGLServerPluginManager : + public ignition::gazebo::System, + public ignition::gazebo::ISystemConfigure, + public ignition::gazebo::ISystemPreUpdate, + public ignition::gazebo::ISystemPostUpdate { + + public: + RGLServerPluginManager(); + + ~RGLServerPluginManager() override; + + // only called once, when plugin is being loaded + void Configure( + const ignition::gazebo::Entity& entity, + const std::shared_ptr& sdf, + ignition::gazebo::EntityComponentManager& ecm, + ignition::gazebo::EventManager& eventMgr) override; + + // called every time before physics update runs (can change entities) + void PreUpdate( + const ignition::gazebo::UpdateInfo& info, + ignition::gazebo::EntityComponentManager& ecm) override; + + // called every time after physics runs (can't change entities) + void PostUpdate( + const ignition::gazebo::UpdateInfo& info, + const ignition::gazebo::EntityComponentManager& ecm) override; + + ////////////////////////////// Utils ///////////////////////////////// + + static ignition::math::Pose3 FindWorldPose( + const ignition::gazebo::Entity& entity, + const ignition::gazebo::EntityComponentManager& ecm); + + // get the local to global transform matrix + static rgl_mat3x4f GetRglMatrix(ignition::gazebo::Entity entity, + const ignition::gazebo::EntityComponentManager& ecm); + + // gazebo mesh factory had problems with adding multiple floats becoming unreliable + static float RoundFloat(float value); + + private: + ////////////////////////////////////////////// Variables ///////////////////////////////////////////// + ////////////////////////////// Lidar //////////////////////////////// + // contains pointers to all entities that were loaded to rgl (as well as to their meshes) + std::unordered_map> entities_in_rgl; + + // the entity ids, that the lidars are attached to + std::unordered_set gazebo_lidars; + + // all entities, that the lidar should ignore + std::unordered_set lidar_ignore; + + ////////////////////////////// Mesh ///////////////////////////////// + + ignition::common::MeshManager* mesh_manager{ignition::common::MeshManager::Instance()}; + + ////////////////////////////////////////////// Functions ///////////////////////////////////////////// + ////////////////////////////// Scene //////////////////////////////// + + bool CheckNewLidars( + ignition::gazebo::Entity entity, + const ignition::gazebo::EntityComponentManager& ecm); + + bool CheckRemovedLidars( + ignition::gazebo::Entity entity, + const ignition::gazebo::EntityComponentManager& ecm); + + bool LoadEntityToRGL( + const ignition::gazebo::Entity& entity, + const ignition::gazebo::components::Visual*, + const ignition::gazebo::components::Geometry* geometry); + + bool RemoveEntityFromRGL( + const ignition::gazebo::Entity& entity, + const ignition::gazebo::components::Visual*, + const ignition::gazebo::components::Geometry*); + + void UpdateRGLEntityPose(const ignition::gazebo::EntityComponentManager& ecm); + + ////////////////////////////// Mesh ///////////////////////////////// + + const ignition::common::Mesh* LoadBox( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z); + + const ignition::common::Mesh* LoadCapsule(const sdf::Geometry& data); + + const ignition::common::Mesh* LoadCylinder( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z); + + const ignition::common::Mesh* LoadEllipsoid( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z); + + const ignition::common::Mesh* LoadMesh( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z); + + const ignition::common::Mesh* LoadPlane( + const sdf::Geometry& data, + double& scale_x, + double& scale_y); + + const ignition::common::Mesh* LoadSphere( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z); + + // also gets the scale of the mesh + const ignition::common::Mesh* GetMeshPointer( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z); + + bool GetMesh( + const sdf::Geometry& data, + size_t& vertex_count, + size_t& triangle_count, + std::vector& vertices, + std::vector& triangles); + + bool LoadMeshToRGL(rgl_mesh_t* new_mesh, const sdf::Geometry& data); + }; +} diff --git a/RGLServerPlugin/src/Lidar.cc b/RGLServerPlugin/src/Lidar.cc new file mode 100644 index 0000000..2741867 --- /dev/null +++ b/RGLServerPlugin/src/Lidar.cc @@ -0,0 +1,126 @@ +#include "RGLServerPluginInstance.hh" +#include "RGLServerPluginManager.hh" + +#define RAYS_IN_ONE_DIR 1000 + +using namespace rgl; + +void RGLServerPluginInstance::CreateLidar(ignition::gazebo::Entity entity) { + updates_between_raytraces = std::chrono::duration_cast(time_between_raytraces).count(); + + ignmsg << "attached to: " << entity << std::endl; + gazebo_lidar = entity; + static int next_free_id = 0; + lidar_id = next_free_id; + next_free_id++; + + rgl_configure_logging(RGL_LOG_LEVEL_DEBUG, nullptr, true); + size_t rays = RAYS_IN_ONE_DIR * RAYS_IN_ONE_DIR; + std::vector ray_tf; + ignition::math::Angle X; + ignition::math::Angle Y; + double unit_angle = ignition::math::Angle::TwoPi.Radian() / RAYS_IN_ONE_DIR; + for (int i = 0; i < RAYS_IN_ONE_DIR; ++i, X.SetRadian(unit_angle * i)) { + for (int j = 0; j < RAYS_IN_ONE_DIR; ++j, Y.SetRadian(unit_angle * j)) { + ignition::math::Quaterniond quaternion(0, X.Radian(), Y.Radian()); + ignition::math::Matrix4d matrix4D(quaternion); + rgl_mat3x4f rgl_matrix; + for (int l = 0; l < 3; ++l) { + for (int m = 0; m < 4; ++m) { + rgl_matrix.value[l][m] = static_cast(matrix4D(l, m)); + } + } + ray_tf.push_back(rgl_matrix); + } + } + RGL_CHECK(rgl_lidar_create(&rgl_lidar, ray_tf.data(), rays)); + pointcloud_publisher = node.Advertise( + "/RGL_point_cloud_" + std::to_string(lidar_id)); +} + + + +void RGLServerPluginInstance::UpdateLidarPose(const ignition::gazebo::EntityComponentManager& ecm) { + if (!lidar_exists) { + return; + } + auto rgl_pose_matrix = RGLServerPluginManager::GetRglMatrix(gazebo_lidar, ecm); + RGL_CHECK(rgl_lidar_set_pose(rgl_lidar, &rgl_pose_matrix)); + + /// Debug printf +// ignmsg << "lidar: " << gazebo_lidar << " rgl_pose_matrix: " << std::endl; +// for (int i = 0; i < 3; ++i) { +// for (int j = 0; j < 4; ++j) { +// ignmsg << rgl_pose_matrix.value[i][j] << " "; +// } +// ignmsg << std::endl; +// } + +} + +void RGLServerPluginInstance::RayTrace(ignition::gazebo::EntityComponentManager& ecm, + std::chrono::steady_clock::duration sim_time, bool paused) { + if (!lidar_exists) { + return; + } + + current_update++; + + if (!paused && sim_time < last_raytrace_time + time_between_raytraces) { + return; + } + if (!paused) { + last_raytrace_time = sim_time; + } + + if (paused && current_update < last_raytrace_update + updates_between_raytraces) { + return; + } + + last_raytrace_update = current_update; + + RGL_CHECK(rgl_lidar_raytrace_async(nullptr, rgl_lidar)); + + int hitpoint_count = 0; + RGL_CHECK(rgl_lidar_get_output_size(rgl_lidar, &hitpoint_count)); + if (hitpoint_count == 0) return; + std::vector results(hitpoint_count, rgl_vec3f()); + RGL_CHECK(rgl_lidar_get_output_data(rgl_lidar, RGL_FORMAT_XYZ, results.data())); + + ignmsg << "Lidar id: " << lidar_id << " Got " << hitpoint_count << " hitpoint(s)\n"; +// for (int i = 0; i < hitpoint_count; ++i) { +// ignmsg << " hit: " << i << " coordinates: " << results[i].value[0] << "," << results[i].value[1] << "," +// << results[i].value[2] << std::endl; +// } + + // Create message + ignition::msgs::PointCloudPacked point_cloud_msg; + ignition::msgs::InitPointCloudPacked(point_cloud_msg, "some_frame", true, + {{"xyz", ignition::msgs::PointCloudPacked::Field::FLOAT32}}); + point_cloud_msg.mutable_data()->resize(hitpoint_count * point_cloud_msg.point_step()); + point_cloud_msg.set_height(1); + point_cloud_msg.set_width(hitpoint_count); + + // Populate message + ignition::msgs::PointCloudPackedIterator xIter(point_cloud_msg, "x"); + ignition::msgs::PointCloudPackedIterator yIter(point_cloud_msg, "y"); + ignition::msgs::PointCloudPackedIterator zIter(point_cloud_msg, "z"); + + for (int i = 0; i < hitpoint_count; ++i, ++xIter, ++yIter, ++zIter) + { + *xIter = results[i].value[0]; + *yIter = results[i].value[1]; + *zIter = results[i].value[2]; + } + + pointcloud_publisher.Publish(point_cloud_msg); +} + +bool RGLServerPluginInstance::CheckLidarExists(ignition::gazebo::Entity entity) { + if (entity == gazebo_lidar) { + lidar_exists = false; + rgl_lidar_destroy(rgl_lidar); + pointcloud_publisher.Publish(ignition::msgs::PointCloudPacked()); + } + return true; +} diff --git a/RGLServerPlugin/src/Mesh.cc b/RGLServerPlugin/src/Mesh.cc new file mode 100644 index 0000000..75f76fc --- /dev/null +++ b/RGLServerPlugin/src/Mesh.cc @@ -0,0 +1,278 @@ +#include "RGLServerPluginManager.hh" + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#define UNIT_BOX_TEXT "unit_box" +#define UNIT_CYLINDER_TEXT "unit_cylinder" +#define UNIT_PLANE_TEXT "unit_plane" +#define UNIT_SPHERE_TEXT "unit_sphere" +#define RGL_CAPSULE_TEXT "RGLGazeboPlugin_capsule_" + +#define CAPSULE_RINGS 1 +#define CAPSULE_SEGMENTS 32 + +using namespace rgl; + +const ignition::common::Mesh* RGLServerPluginManager::LoadBox( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z) { + + std::cout << "BOX geometry" << std::endl; + + auto size = data.BoxShape()->Size(); + + scale_x = size.X(); + scale_y = size.Y(); + scale_z = size.Z(); + + return mesh_manager->MeshByName(UNIT_BOX_TEXT); +} + +const ignition::common::Mesh* RGLServerPluginManager::LoadCapsule(const sdf::Geometry& data) { + std::cout << "CAPSULE geometry" << std::endl; + + static unsigned int capsule_id = 0; + + auto shape = data.CapsuleShape(); + + mesh_manager->CreateCapsule( + RGL_CAPSULE_TEXT + std::to_string(capsule_id), + shape->Radius(), + shape->Length(), + CAPSULE_RINGS, + CAPSULE_SEGMENTS); + + capsule_id++; + + return mesh_manager->MeshByName(RGL_CAPSULE_TEXT + std::to_string(capsule_id - 1)); +} + +const ignition::common::Mesh* RGLServerPluginManager::LoadCylinder( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z) { + + std::cout << "CYLINDER geometry" << std::endl; + + auto shape = data.CylinderShape(); + + scale_x = shape->Radius() * 2; + scale_y = shape->Radius() * 2; + scale_z = shape->Length(); + + return mesh_manager->MeshByName(UNIT_CYLINDER_TEXT); +} + +const ignition::common::Mesh* RGLServerPluginManager::LoadEllipsoid( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z) { + + std::cout << "ELLIPSOID geometry" << std::endl; + + auto shape = data.EllipsoidShape()->Radii(); + + scale_x = shape.X() * 2; + scale_y = shape.Y() * 2; + scale_z = shape.Z() * 2; + + return mesh_manager->MeshByName(UNIT_SPHERE_TEXT); +} + +const ignition::common::Mesh* RGLServerPluginManager::LoadMesh( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z) { + + std::cout << "MESH geometry" << std::endl; + + auto scale = data.MeshShape()->Scale(); + + scale_x = scale.X(); + scale_y = scale.Y(); + scale_z = scale.Z(); + + return mesh_manager->MeshByName( + ignition::gazebo::asFullPath( + data.MeshShape()->Uri(), + data.MeshShape()->FilePath())); +} + +const ignition::common::Mesh* RGLServerPluginManager::LoadPlane( + const sdf::Geometry& data, + double& scale_x, + double& scale_y) { + + std::cout << "PLANE geometry" << std::endl; + + auto size = data.PlaneShape()->Size(); + + scale_x = size.X() * 2; + scale_y = size.Y() * 2; + + return mesh_manager->MeshByName(UNIT_PLANE_TEXT); +} + +const ignition::common::Mesh* RGLServerPluginManager::LoadSphere( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z) { + + std::cout << "SPHERE geometry" << std::endl; + + auto radius = data.SphereShape()->Radius(); + + scale_x = radius * 2; + scale_y = radius * 2; + scale_z = radius * 2; + + return mesh_manager->MeshByName(UNIT_SPHERE_TEXT); +} + +const ignition::common::Mesh* RGLServerPluginManager::GetMeshPointer( + const sdf::Geometry& data, + double& scale_x, + double& scale_y, + double& scale_z) { + + const ignition::common::Mesh* mesh_pointer; + + switch (data.Type()) { + case sdf::GeometryType::BOX: + mesh_pointer = LoadBox(data, scale_x, scale_y, scale_z); + break; + case sdf::GeometryType::CAPSULE: + mesh_pointer = LoadCapsule(data); + break; + case sdf::GeometryType::CYLINDER: + mesh_pointer = LoadCylinder(data, scale_x, scale_y, scale_z); + break; + case sdf::GeometryType::ELLIPSOID: + mesh_pointer = LoadEllipsoid(data, scale_x, scale_y, scale_z); + break; + case sdf::GeometryType::EMPTY: + ignerr << "EMPTY geometry" << std::endl; + return nullptr; + case sdf::GeometryType::MESH: + mesh_pointer = LoadMesh(data, scale_x, scale_y, scale_z); + break; + case sdf::GeometryType::PLANE: + mesh_pointer = LoadPlane(data, scale_x, scale_y); + break; + case sdf::GeometryType::SPHERE: + mesh_pointer = LoadSphere(data, scale_x, scale_y, scale_z); + break; + default: + ignerr << "geometry type not supported yet" << std::endl; + return nullptr; + } + if (nullptr == mesh_pointer) { + std::cout << "Error in importing mesh - it will not be loaded to RGL\n"; + } + return mesh_pointer; +} + +bool RGLServerPluginManager::GetMesh( + const sdf::Geometry& data, + size_t& vertex_count, + size_t& triangle_count, + std::vector& vertices, + std::vector& triangles) { + + double scale_x = 1; + double scale_y = 1; + double scale_z = 1; + + auto mesh_common = GetMeshPointer(data, scale_x, scale_y, scale_z); + if (nullptr == mesh_common) return false; + + vertex_count = mesh_common->VertexCount(); + triangle_count = mesh_common->IndexCount() / 3; + + vertices.resize(vertex_count); + + double* vertices_double_arr = nullptr; + int* triangles_arr = nullptr; + + mesh_common->FillArrays(&vertices_double_arr, &triangles_arr); + + auto* beginning = reinterpret_cast(triangles_arr); + auto* end = reinterpret_cast(triangles_arr + sizeof(rgl_vec3i) * triangle_count); + triangles.assign(beginning, end); + + int v_index = 0; + for (int i = 0; i < vertex_count; ++i) { + for (int j = 0; j < 3; ++j) { + auto vertex_coord = vertices_double_arr[v_index]; + switch (j) { + case 0: + vertex_coord *= scale_x; + break; + case 1: + vertex_coord *= scale_y; + break; + case 2: + vertex_coord *= scale_z; + break; + default:; + } + vertices[i].value[j] = RoundFloat(static_cast(vertex_coord)); + v_index++; + } + } + + /// Debug printf +// int count = 0; +// std::cout << "vertices: "; +// for (int i = 0; i < vertex_count; ++i) { +// std::cout << count << ": "; +// count++; +// for (int j = 0; j < 3; ++j) { +// std::cout << vertices[i].value[j] << ","; +// } +// std::cout << " "; +// } +// std::cout << "\n"; +// +// std::cout << "triangles: "; +// for (int i = 0; i < triangle_count; ++i) { +// for (int j = 0; j < 3; ++j) { +// std::cout << (*triangles)[i].value[j] << ","; +// } +// std::cout << " "; +// } +// std::cout << "\n"; + + free(vertices_double_arr); + return true; +} + +bool RGLServerPluginManager::LoadMeshToRGL( + rgl_mesh_t* new_mesh, + const sdf::Geometry& data) { + + size_t vertex_count; + size_t triangle_count; + std::vector vertices; + std::vector triangles; + + if (!GetMesh(data, vertex_count, triangle_count, vertices, triangles)) return false; + RGL_CHECK(rgl_mesh_create(new_mesh, vertices.data(), vertex_count, triangles.data(), triangle_count)); + + return true; +} diff --git a/RGLServerPlugin/src/RGLServerPluginInstance.cc b/RGLServerPlugin/src/RGLServerPluginInstance.cc new file mode 100644 index 0000000..f59f936 --- /dev/null +++ b/RGLServerPlugin/src/RGLServerPluginInstance.cc @@ -0,0 +1,44 @@ +#include "RGLServerPluginInstance.hh" + +#include +#include + +IGNITION_ADD_PLUGIN( + rgl::RGLServerPluginInstance, + ignition::gazebo::System, + rgl::RGLServerPluginInstance::ISystemConfigure, + rgl::RGLServerPluginInstance::ISystemPreUpdate, + rgl::RGLServerPluginInstance::ISystemPostUpdate +) + +using namespace rgl; +using namespace std::placeholders; + +RGLServerPluginInstance::RGLServerPluginInstance() = default; + +RGLServerPluginInstance::~RGLServerPluginInstance() = default; + +void RGLServerPluginInstance::Configure( + const ignition::gazebo::Entity& entity, + const std::shared_ptr&, + ignition::gazebo::EntityComponentManager& ecm, + ignition::gazebo::EventManager& evm) { + + CreateLidar(entity); +} + +void RGLServerPluginInstance::PreUpdate( + const ignition::gazebo::UpdateInfo& info, + ignition::gazebo::EntityComponentManager& ecm) { + + ecm.EachRemoved<>(std::bind(&RGLServerPluginInstance::CheckLidarExists, this, _1)); + + RayTrace(ecm, info.simTime, info.paused); +} + +void RGLServerPluginInstance::PostUpdate( + const ignition::gazebo::UpdateInfo& info, + const ignition::gazebo::EntityComponentManager& ecm) { + + UpdateLidarPose(ecm); +} diff --git a/RGLServerPlugin/src/RGLServerPluginManager.cc b/RGLServerPlugin/src/RGLServerPluginManager.cc new file mode 100644 index 0000000..67cf63e --- /dev/null +++ b/RGLServerPlugin/src/RGLServerPluginManager.cc @@ -0,0 +1,56 @@ +#include "RGLServerPluginManager.hh" + +#include +#include + +IGNITION_ADD_PLUGIN( + rgl::RGLServerPluginManager, + ignition::gazebo::System, + rgl::RGLServerPluginManager::ISystemConfigure, + rgl::RGLServerPluginManager::ISystemPreUpdate, + rgl::RGLServerPluginManager::ISystemPostUpdate +) + +using namespace rgl; +using namespace std::placeholders; + +RGLServerPluginManager::RGLServerPluginManager() = default; + +RGLServerPluginManager::~RGLServerPluginManager() = default; + +void RGLServerPluginManager::Configure( + const ignition::gazebo::Entity& entity, + const std::shared_ptr&, + ignition::gazebo::EntityComponentManager& ecm, + ignition::gazebo::EventManager& evm) { + + ecm.Each<>([&](const ignition::gazebo::Entity& entity)-> bool { + return CheckNewLidars(entity, ecm);}); + + ecm.Each + (std::bind(&RGLServerPluginManager::LoadEntityToRGL, this, _1, _2, _3)); +} + +void RGLServerPluginManager::PreUpdate( + const ignition::gazebo::UpdateInfo& info, + ignition::gazebo::EntityComponentManager& ecm) { +} + +void RGLServerPluginManager::PostUpdate( + const ignition::gazebo::UpdateInfo& info, + const ignition::gazebo::EntityComponentManager& ecm) { + + ecm.EachNew<>([&](const ignition::gazebo::Entity& entity)-> bool { + return CheckNewLidars(entity, ecm);}); + + ecm.EachNew + (std::bind(&RGLServerPluginManager::LoadEntityToRGL, this, _1, _2, _3)); + + ecm.EachRemoved<>([&](const ignition::gazebo::Entity& entity)-> bool { + return CheckRemovedLidars(entity, ecm);}); + + ecm.EachRemoved + (std::bind(&RGLServerPluginManager::RemoveEntityFromRGL, this, _1, _2, _3)); + + UpdateRGLEntityPose(ecm); +} diff --git a/RGLServerPlugin/src/Scene.cc b/RGLServerPlugin/src/Scene.cc new file mode 100644 index 0000000..d880710 --- /dev/null +++ b/RGLServerPlugin/src/Scene.cc @@ -0,0 +1,94 @@ +#include "RGLServerPluginManager.hh" + +#include + +#define RGLINSTANCE "rgl::RGLServerPluginInstance" + +using namespace rgl; + +#pragma clang diagnostic push +#pragma ide diagnostic ignored "ConstantFunctionResult" + +// always returns true, because the ecm will stop if it encounters false +bool RGLServerPluginManager::CheckNewLidars( + ignition::gazebo::Entity entity, + const ignition::gazebo::EntityComponentManager& ecm) { + + auto data = ecm.ComponentData(entity); + if (data == std::nullopt) return true; + auto plugins = data->plugins(); + for (const auto& plugin : plugins) { + if (plugin.name() == RGLINSTANCE) { + gazebo_lidars.insert(entity); + for (auto descendant: ecm.Descendants(entity)) { + lidar_ignore.insert(descendant); + } + } + } + return true; +} + +// always returns true, because the ecm will stop if it encounters false +bool RGLServerPluginManager::CheckRemovedLidars( + ignition::gazebo::Entity entity, + const ignition::gazebo::EntityComponentManager& ecm) { + if (!gazebo_lidars.contains(entity)) { + return true; + } + for (auto descendant: ecm.Descendants(entity)) { + lidar_ignore.erase(descendant); + } + gazebo_lidars.erase(entity); + return true; +} + +// always returns true, because the ecm will stop if it encounters false +bool RGLServerPluginManager::LoadEntityToRGL( + const ignition::gazebo::Entity& entity, + const ignition::gazebo::components::Visual*, + const ignition::gazebo::components::Geometry* geometry) { + if (lidar_ignore.contains(entity)) return true; + if (entities_in_rgl.contains(entity)) return true; + rgl_mesh_t new_mesh; + if (!LoadMeshToRGL(&new_mesh, geometry->Data())) return true; + rgl_entity_t new_rgl_entity; + RGL_CHECK(rgl_entity_create(&new_rgl_entity, nullptr, new_mesh)); + entities_in_rgl.insert(std::make_pair(entity, std::make_pair(new_rgl_entity, new_mesh))); + ignmsg << "Added entity: " << entity << std::endl; + return true; +} + +// always returns true, because the ecm will stop if it encounters false +bool RGLServerPluginManager::RemoveEntityFromRGL( + const ignition::gazebo::Entity& entity, + const ignition::gazebo::components::Visual*, + const ignition::gazebo::components::Geometry*) { + if (lidar_ignore.contains(entity)) { + lidar_ignore.erase(entity); + return true; + } + if (!entities_in_rgl.contains(entity)) return true; + RGL_CHECK(rgl_entity_destroy(entities_in_rgl.at(entity).first)); + RGL_CHECK(rgl_mesh_destroy(entities_in_rgl.at(entity).second)); + entities_in_rgl.erase(entity); + ignmsg << "Removed entity: " << entity << std::endl; + return true; +} +#pragma clang diagnostic pop + +void RGLServerPluginManager::UpdateRGLEntityPose(const ignition::gazebo::EntityComponentManager& ecm) { + for (auto entity: entities_in_rgl) { + auto rgl_matrix = GetRglMatrix(entity.first, ecm); + RGL_CHECK(rgl_entity_set_pose(entity.second.first, &rgl_matrix)); + + /// Debug printf +// ignmsg << "entity: " << entity.first << " rgl_matrix: " << std::endl; +// for (int i = 0; i < 3; ++i) { +// for (int j = 0; j < 4; ++j) { +// ignmsg << rgl_matrix.value[i][j] << " "; +// } +// ignmsg << std::endl; +// } + + } +} diff --git a/RGLServerPlugin/src/Utils.cc b/RGLServerPlugin/src/Utils.cc new file mode 100644 index 0000000..d708e61 --- /dev/null +++ b/RGLServerPlugin/src/Utils.cc @@ -0,0 +1,59 @@ +#include "RGLServerPluginManager.hh" + +#include + +#define ROUND_BY_VALUE 10000 + +using namespace rgl; + +ignition::math::Pose3 RGLServerPluginManager::FindWorldPose( + const ignition::gazebo::Entity& entity, + const ignition::gazebo::EntityComponentManager& ecm) { + + auto local_pose = ecm.Component(entity); + if (nullptr == local_pose) { + std::cout << "pose data missing - using default pose (0, 0, 0, 0, 0, 0)\n"; + return ignition::math::Pose3d::Zero; + } + auto world_pose = local_pose->Data(); + + ignition::gazebo::Entity this_entity = entity; + ignition::gazebo::Entity parent; + + while ((parent = ecm.ParentEntity(this_entity)) != WORLD_ENTITY_ID) { + auto parent_pose = ecm.Component(parent); + if (nullptr == parent_pose) { + std::cout << "pose data missing - using default pose (0, 0, 0, 0, 0, 0)\n"; + return ignition::math::Pose3d::Zero; + } + world_pose += parent_pose->Data(); + this_entity = parent; + } + + return world_pose; +} + +rgl_mat3x4f RGLServerPluginManager::GetRglMatrix( + ignition::gazebo::Entity entity, + const ignition::gazebo::EntityComponentManager& ecm) { + + auto gazebo_matrix = ignition::math::Matrix4(FindWorldPose(entity, ecm)); + + /// Debug printf +// ignmsg << "entity: " << entity << " gazebo_matrix: " << gazebo_matrix << std::endl; + + rgl_mat3x4f rgl_matrix; + + for (int i = 0; i < 3; ++i) { + for (int j = 0; j < 4; ++j) { + rgl_matrix.value[i][j] = static_cast(gazebo_matrix(i, j)); + } + } + + return rgl_matrix; +} + + +float RGLServerPluginManager::RoundFloat(float value) { + return std::roundf(value * ROUND_BY_VALUE) / ROUND_BY_VALUE; +} diff --git a/test_world/actor_world.sdf b/test_world/actor_world.sdf new file mode 100644 index 0000000..b4a97a7 --- /dev/null +++ b/test_world/actor_world.sdf @@ -0,0 +1,240 @@ + + + + + + + ogre2 + + + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + true + + + true + + + + + 0 0 1 + 100 100 + + + + + + + + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + + 1 + 0 + 0 + 1 + 0 + 1 + + + false + + 0 0 0 0 -0 0 + false + + + + + 0 0 0.7 0 -0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + 0 0 0 0 -0 0 + + + + + 1 1 1 + + + + + + + + + + + + + + 1 1 1 + + + + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + 0.3 0.5 0.3 1 + + + 0 0 0 0 -0 0 + false + + false + false + + + + + 0 0 5 0 -0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + 0 0 0 0 -0 0 + + + + + 1 1 1 + + + + + + + + + + + + + + 1 1 1 + + + + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + 0.3 0.5 0.3 1 + + + 0 0 0 0 -0 0 + false + + false + false + + + 0 0 10 0 -0 0 + true + 1 + -0.5 0.1 -0.9 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.01 + 0.90000000000000002 + 0.001 + + + 0 + 0 + 0 + + + + 0 0 10 0 -0 0 + + + + + meshes/minecartengine.dae + 20.0 20.0 20.0 + + + + + + + meshes/minecartengine.dae + 20.0 20.0 20.0 + + MineCartEngine +
false
+
+
+
+ + 1.0 1.0 1.0 + 1.0 1.0 1.0 + + + materials/textures/MineCartEngine_Albedo.png + materials/textures/MineCartEngine_Metalness.png + materials/textures/MineCartEngine_Roughness.png + + + + + +
+ +
+
+
diff --git a/test_world/materials/scripts/model.material b/test_world/materials/scripts/model.material new file mode 100644 index 0000000..5fc9691 --- /dev/null +++ b/test_world/materials/scripts/model.material @@ -0,0 +1,27 @@ + +material UrbanTile/MineCartEngine_Diffuse +{ + technique + { + pass + { + texture_unit + { + texture MineCartEngine_Albedo.png + } + } + } + } +material UrbanTile/MineCart_Diffuse +{ + technique + { + pass + { + texture_unit + { + texture MineCart_Albedo.png + } + } + } + } \ No newline at end of file diff --git a/test_world/materials/textures/MineCartEngine_Albedo.png b/test_world/materials/textures/MineCartEngine_Albedo.png new file mode 100644 index 0000000..4fcce37 Binary files /dev/null and b/test_world/materials/textures/MineCartEngine_Albedo.png differ diff --git a/test_world/materials/textures/MineCartEngine_Metalness.png b/test_world/materials/textures/MineCartEngine_Metalness.png new file mode 100644 index 0000000..484da25 Binary files /dev/null and b/test_world/materials/textures/MineCartEngine_Metalness.png differ diff --git a/test_world/materials/textures/MineCartEngine_Roughness.png b/test_world/materials/textures/MineCartEngine_Roughness.png new file mode 100644 index 0000000..64142a9 Binary files /dev/null and b/test_world/materials/textures/MineCartEngine_Roughness.png differ diff --git a/test_world/meshes/minecartengine.dae b/test_world/meshes/minecartengine.dae new file mode 100644 index 0000000..2edfabb --- /dev/null +++ b/test_world/meshes/minecartengine.dae @@ -0,0 +1,18648 @@ + + + + + + FBX COLLADA exporter + + + 2020-08-31T21:17:01Z + + 2020-08-31T21:17:01Z + + + + <unit meter="0.10000" name="meter"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_images> + <image id="MapFBXASC032FBXASC0356-image" name="MapFBXASC032FBXASC0356"> + <init_from>../materials/textures/MineCartEngine_Albedo.png</init_from> + </image> + </library_images> + <library_materials> + <material id="MineCartEngine_ncl1_1" name="MineCartEngine_ncl1_1"> + <instance_effect url="#MineCartEngine_ncl1_1-fx"/> + </material> + </library_materials> + <library_effects> + <effect id="MineCartEngine_ncl1_1-fx" name="MineCartEngine_ncl1_1"> + <profile_COMMON> + <technique sid="standard"> + <phong> + <emission> + <color sid="emission">0.000000 0.000000 0.000000 1.000000</color> + </emission> + <ambient> + <color sid="ambient">0.588235 0.588235 0.588235 1.000000</color> + </ambient> + <diffuse> + <texture texture="MapFBXASC032FBXASC0356-image" texcoord="CHANNEL0"> + <extra> + <technique profile="MAYA"> + <wrapU sid="wrapU0">TRUE</wrapU> + <wrapV sid="wrapV0">TRUE</wrapV> + <blend_mode>ADD</blend_mode> + </technique> + </extra> + </texture> + </diffuse> + <specular> + <color sid="specular">0.000000 0.000000 0.000000 1.000000</color> + </specular> + <shininess> + <float sid="shininess">2.000000</float> + </shininess> + <reflective> + <color sid="reflective">0.000000 0.000000 0.000000 1.000000</color> + </reflective> + <reflectivity> + <float sid="reflectivity">1.000000</float> + </reflectivity> + <transparent opaque="RGB_ZERO"> + <color sid="transparent">1.000000 1.000000 1.000000 1.000000</color> + </transparent> + <transparency> + <float sid="transparency">0.000000</float> + </transparency> + </phong> + </technique> + </profile_COMMON> + </effect> + </library_effects> + <library_geometries> + <geometry id="MineCartEngine-lib" name="MineCartEngineMesh"> + <mesh> + <source id="MineCartEngine-POSITION"> + <float_array id="MineCartEngine-POSITION-array" count="6678"> +-3.059031 3.294444 5.476800 +-3.079404 3.221359 5.441512 +-3.057944 3.149528 5.478682 +-3.016111 3.150783 5.551139 +-2.995737 3.223868 5.586427 +-3.017197 3.295698 5.549257 +-3.086110 3.262045 5.514787 +-3.097294 3.221924 5.495415 +-3.085513 3.182492 5.515820 +-3.062548 3.183181 5.555596 +-3.051364 3.223302 5.574968 +-3.063144 3.262734 5.554564 +-3.073804 3.503207 5.451212 +-3.073804 3.419530 5.451212 +-3.037571 3.377693 5.513970 +-3.001338 3.419530 5.576727 +-3.001338 3.503207 5.576727 +-3.037571 3.545044 5.513970 +-3.094219 3.484336 5.500740 +-3.094219 3.438401 5.500740 +-3.074329 3.415432 5.535192 +-3.054438 3.438401 5.569643 +-3.054438 3.484336 5.569643 +-3.074329 3.507304 5.535192 +-3.194699 3.276637 5.241815 +-3.202117 3.194286 5.228966 +-3.170168 3.140262 5.284305 +-3.130800 3.168590 5.352492 +-3.123382 3.250940 5.365340 +-3.155332 3.304964 5.310001 +-3.217047 3.252270 5.287996 +-3.221119 3.207063 5.280943 +-3.203580 3.177406 5.311322 +-3.181968 3.192956 5.348755 +-3.177896 3.238163 5.355808 +-3.195435 3.267821 5.325429 +-3.194282 3.516364 5.242538 +-3.202330 3.434250 5.228599 +-3.170797 3.379255 5.283215 +-3.131217 3.406374 5.351769 +-3.123170 3.488487 5.365708 +-3.154702 3.543482 5.311092 +-3.216818 3.491559 5.288393 +-3.221236 3.446481 5.280741 +-3.203926 3.416291 5.310723 +-3.182198 3.431178 5.348358 +-3.177780 3.476255 5.356010 +-3.195090 3.506446 5.326028 +-3.059031 -3.294434 5.476800 +-3.079404 -3.221350 5.441512 +-3.057944 -3.149519 5.478682 +-3.016111 -3.150774 5.551139 +-2.995737 -3.223858 5.586427 +-3.017197 -3.295689 5.549257 +-3.086110 -3.262038 5.514787 +-3.097294 -3.221917 5.495415 +-3.085513 -3.182484 5.515820 +-3.062548 -3.183173 5.555596 +-3.051364 -3.223294 5.574968 +-3.063144 -3.262726 5.554564 +-3.073804 -3.503197 5.451212 +-3.073804 -3.419522 5.451212 +-3.037571 -3.377684 5.513970 +-3.001338 -3.419522 5.576727 +-3.001338 -3.503197 5.576727 +-3.037571 -3.545037 5.513970 +-3.094219 -3.484328 5.500740 +-3.094219 -3.438391 5.500740 +-3.074329 -3.415425 5.535192 +-3.054438 -3.438391 5.569643 +-3.054438 -3.484328 5.569643 +-3.074329 -3.507296 5.535192 +-3.194699 -3.276629 5.241815 +-3.202117 -3.194277 5.228966 +-3.170168 -3.140254 5.284305 +-3.130800 -3.168581 5.352492 +-3.123382 -3.250931 5.365340 +-3.155332 -3.304955 5.310001 +-3.217047 -3.252263 5.287996 +-3.221119 -3.207055 5.280943 +-3.203580 -3.177397 5.311322 +-3.181968 -3.192948 5.348755 +-3.177896 -3.238156 5.355808 +-3.195435 -3.267811 5.325429 +-3.194282 -3.516356 5.242538 +-3.202330 -3.434243 5.228599 +-3.170797 -3.379246 5.283215 +-3.131217 -3.406365 5.351769 +-3.123170 -3.488478 5.365708 +-3.154702 -3.543473 5.311092 +-3.216818 -3.491551 5.288393 +-3.221236 -3.446473 5.280741 +-3.203926 -3.416283 5.310723 +-3.182198 -3.431170 5.348358 +-3.177780 -3.476246 5.356010 +-3.195090 -3.506438 5.326028 +3.059031 3.294444 5.476800 +3.079405 3.221359 5.441512 +3.057945 3.149528 5.478682 +3.016111 3.150783 5.551139 +2.995738 3.223868 5.586427 +3.017198 3.295698 5.549257 +3.086110 3.262045 5.514787 +3.097295 3.221924 5.495415 +3.085514 3.182492 5.515820 +3.062548 3.183181 5.555596 +3.051364 3.223302 5.574968 +3.063145 3.262734 5.554564 +3.073804 3.503207 5.451212 +3.073804 3.419530 5.451212 +3.037571 3.377693 5.513970 +3.001339 3.419530 5.576727 +3.001338 3.503207 5.576727 +3.037571 3.545044 5.513970 +3.094220 3.484336 5.500740 +3.094220 3.438401 5.500740 +3.074329 3.415432 5.535192 +3.054439 3.438401 5.569643 +3.054439 3.484336 5.569643 +3.074329 3.507304 5.535192 +3.194700 3.276637 5.241815 +3.202118 3.194286 5.228966 +3.170168 3.140262 5.284305 +3.130801 3.168590 5.352492 +3.123382 3.250940 5.365340 +3.155332 3.304964 5.310001 +3.217048 3.252270 5.287996 +3.221120 3.207063 5.280943 +3.203580 3.177406 5.311322 +3.181969 3.192956 5.348755 +3.177897 3.238163 5.355808 +3.195436 3.267821 5.325429 +3.194283 3.516364 5.242538 +3.202330 3.434250 5.228599 +3.170798 3.379255 5.283215 +3.131218 3.406374 5.351769 +3.123170 3.488487 5.365708 +3.154703 3.543482 5.311092 +3.216819 3.491559 5.288393 +3.221236 3.446481 5.280741 +3.203926 3.416291 5.310723 +3.182198 3.431178 5.348358 +3.177780 3.476255 5.356010 +3.195091 3.506446 5.326028 +3.059031 -3.294434 5.476800 +3.079405 -3.221350 5.441512 +3.057945 -3.149519 5.478682 +3.016111 -3.150774 5.551139 +2.995738 -3.223858 5.586427 +3.017198 -3.295689 5.549257 +3.086110 -3.262038 5.514787 +3.097295 -3.221917 5.495415 +3.085514 -3.182484 5.515820 +3.062548 -3.183173 5.555596 +3.051364 -3.223294 5.574968 +3.063145 -3.262726 5.554564 +3.073804 -3.503197 5.451212 +3.073804 -3.419522 5.451212 +3.037571 -3.377684 5.513970 +3.001339 -3.419522 5.576727 +3.001338 -3.503197 5.576727 +3.037571 -3.545037 5.513970 +3.094220 -3.484328 5.500740 +3.094220 -3.438391 5.500740 +3.074329 -3.415425 5.535192 +3.054439 -3.438391 5.569643 +3.054439 -3.484328 5.569643 +3.074329 -3.507296 5.535192 +3.194700 -3.276629 5.241815 +3.202118 -3.194277 5.228966 +3.170168 -3.140254 5.284305 +3.130801 -3.168581 5.352492 +3.123382 -3.250931 5.365340 +3.155332 -3.304955 5.310001 +3.217048 -3.252263 5.287996 +3.221120 -3.207055 5.280943 +3.203580 -3.177397 5.311322 +3.181969 -3.192948 5.348755 +3.177897 -3.238156 5.355808 +3.195436 -3.267811 5.325429 +3.194283 -3.516356 5.242538 +3.202330 -3.434243 5.228599 +3.170798 -3.379246 5.283215 +3.131218 -3.406365 5.351769 +3.123170 -3.488478 5.365708 +3.154703 -3.543473 5.311092 +3.216819 -3.491551 5.288393 +3.221236 -3.446473 5.280741 +3.203926 -3.416283 5.310723 +3.182198 -3.431170 5.348358 +3.177780 -3.476246 5.356010 +3.195091 -3.506438 5.326028 +-2.743104 4.022163 2.034670 +-2.696028 4.022163 2.132280 +-2.587958 4.022163 2.140316 +-2.526963 4.022163 2.050742 +-2.574038 4.022163 1.953132 +-2.682109 4.022163 1.945096 +-2.743104 4.130531 2.034670 +-2.696028 4.130531 2.132280 +-2.587958 4.130531 2.140316 +-2.526963 4.130531 2.050742 +-2.574038 4.130531 1.953132 +-2.682109 4.130531 1.945096 +-2.635033 4.130531 2.042706 +-2.735579 4.022163 1.633953 +-2.720317 4.022163 1.741242 +-2.619772 4.022163 1.781670 +-2.534488 4.022163 1.714808 +-2.549749 4.022163 1.607520 +-2.650295 4.022163 1.567092 +-2.735579 4.130531 1.633953 +-2.720317 4.130531 1.741242 +-2.619772 4.130531 1.781670 +-2.534488 4.130531 1.714808 +-2.549749 4.130531 1.607520 +-2.650295 4.130531 1.567092 +-2.635033 4.130531 1.674381 +2.743104 4.022163 2.034670 +2.696029 4.022163 2.132280 +2.587958 4.022163 2.140316 +2.526964 4.022163 2.050742 +2.574039 4.022163 1.953132 +2.682109 4.022163 1.945096 +2.743104 4.130531 2.034670 +2.696029 4.130531 2.132280 +2.587958 4.130531 2.140316 +2.526964 4.130531 2.050742 +2.574039 4.130531 1.953132 +2.682109 4.130531 1.945096 +2.635034 4.130531 2.042706 +2.735580 4.022163 1.633953 +2.720318 4.022163 1.741242 +2.619773 4.022163 1.781670 +2.534488 4.022163 1.714808 +2.549750 4.022163 1.607520 +2.650295 4.022163 1.567092 +2.735580 4.130531 1.633953 +2.720318 4.130531 1.741242 +2.619773 4.130531 1.781670 +2.534488 4.130531 1.714808 +2.549750 4.130531 1.607520 +2.650295 4.130531 1.567092 +2.635034 4.130531 1.674381 +-2.885000 3.915582 2.195994 +-2.885000 4.022163 2.195994 +-2.885000 3.915582 1.482456 +-2.885000 4.022163 1.482456 +0.000000 4.728328 2.195994 +0.000000 4.621747 2.195994 +0.000000 4.621747 1.482456 +0.000000 4.728328 1.482456 +-2.274725 3.915582 2.195994 +-2.197055 3.993252 2.195994 +-2.379982 4.022163 2.195994 +-2.302313 4.099832 2.195994 +-2.379983 4.022163 1.482456 +-2.302313 4.099833 1.482456 +-2.274724 3.915582 1.482456 +-2.197055 3.993251 1.482456 +-1.808814 4.728328 2.195994 +-2.057661 4.625252 2.195994 +-2.190980 4.378995 2.195994 +-1.808821 4.728328 1.482456 +-2.057663 4.625254 1.482456 +-2.190981 4.378996 1.482456 +-1.703563 4.621747 2.195994 +-1.952405 4.518673 2.195994 +-2.085723 4.272416 2.195994 +-1.703556 4.621747 1.482456 +-1.952403 4.518672 1.482456 +-2.085722 4.272415 1.482456 +2.885001 3.915582 2.195994 +2.885001 4.022163 2.195994 +2.885001 3.915582 1.482456 +2.885001 4.022163 1.482456 +2.274726 3.915582 2.195994 +2.197055 3.993252 2.195994 +2.379982 4.022163 2.195994 +2.302313 4.099832 2.195994 +2.379984 4.022163 1.482456 +2.302313 4.099833 1.482456 +2.274724 3.915582 1.482456 +2.197055 3.993251 1.482456 +1.808814 4.728328 2.195994 +2.057661 4.625252 2.195994 +2.190981 4.378995 2.195994 +1.808821 4.728328 1.482456 +2.057663 4.625254 1.482456 +2.190982 4.378996 1.482456 +1.703563 4.621747 2.195994 +1.952406 4.518673 2.195994 +2.085724 4.272416 2.195994 +1.703557 4.621747 1.482456 +1.952403 4.518672 1.482456 +2.085723 4.272415 1.482456 +-2.738879 1.419696 -0.116527 +-2.738879 1.022744 0.085728 +-2.738879 0.707723 0.400750 +-2.738879 0.505466 0.797701 +-2.738879 0.435773 1.237724 +-2.738879 0.505466 1.677748 +-2.738879 0.707723 2.074699 +-2.738879 1.022744 2.389719 +-2.738879 1.419696 2.591976 +-2.738879 1.859718 2.661669 +-2.738879 2.299739 2.591976 +-2.738879 2.696691 2.389719 +-2.738879 3.011713 2.074699 +-2.738879 3.213968 1.677748 +-2.738879 3.283660 1.237724 +-2.738879 3.213968 0.797701 +-2.738879 3.011713 0.400751 +-2.738879 2.696691 0.085730 +-2.738879 2.299739 -0.116527 +-2.738879 1.859718 -0.186219 +-2.935497 1.419696 -0.116527 +-2.935497 1.022744 0.085728 +-2.935497 0.707723 0.400750 +-2.935497 0.505466 0.797701 +-2.935497 0.435773 1.237724 +-2.935497 0.505466 1.677748 +-2.935497 0.707723 2.074699 +-2.935497 1.022744 2.389719 +-2.935497 1.419696 2.591976 +-2.935497 1.859718 2.661669 +-2.935497 2.299739 2.591976 +-2.935497 2.696691 2.389719 +-2.935497 3.011713 2.074699 +-2.935497 3.213968 1.677748 +-2.935497 3.283660 1.237724 +-2.935497 3.213968 0.797701 +-2.935497 3.011713 0.400751 +-2.935497 2.696691 0.085730 +-2.935497 2.299739 -0.116527 +-2.935475 1.859718 -0.186219 +-2.935497 1.474786 0.053035 +-2.935497 1.127537 0.229966 +-2.935497 0.851958 0.505546 +-2.935497 0.675027 0.852796 +-2.935497 0.614061 1.237725 +-2.935497 0.675027 1.622655 +-2.935497 0.851958 1.969905 +-2.935497 1.127539 2.245484 +-2.935497 1.474786 2.422416 +-2.935497 1.859718 2.483384 +-2.935497 2.244648 2.422416 +-2.935497 2.591897 2.245484 +-2.935497 2.867475 1.969905 +-2.935497 3.044407 1.622655 +-2.935497 3.105376 1.237726 +-2.935497 3.044407 0.852796 +-2.935497 2.867475 0.505546 +-2.935497 2.591897 0.229967 +-2.935497 2.244646 0.053036 +-2.935497 1.859718 -0.007931 +-3.560476 1.474785 0.053022 +-3.560476 1.127537 0.229966 +-3.560476 0.851958 0.505546 +-3.560476 0.675027 0.852796 +-3.560476 0.614061 1.237725 +-3.560476 0.675027 1.622655 +-3.560476 0.851958 1.969905 +-3.560476 1.127539 2.245484 +-3.560476 1.474786 2.422416 +-3.560476 1.859718 2.483384 +-3.560476 2.244648 2.422416 +-3.560476 2.591897 2.245484 +-3.560476 2.867475 1.969905 +-3.560476 3.044407 1.622655 +-3.560476 3.105376 1.237726 +-3.560476 3.044407 0.852796 +-3.560476 2.867475 0.505546 +-3.560476 2.591897 0.229967 +-3.560476 2.244648 0.053023 +-3.560476 1.859718 -0.007957 +-3.404215 2.573705 2.220446 +-3.091758 2.573705 2.220446 +-3.091758 2.235084 2.392983 +-3.404215 2.235084 2.392982 +-3.091758 1.859718 2.452435 +-3.404215 1.859718 2.452435 +-3.091758 1.484351 2.392983 +-3.404215 1.484351 2.392982 +-3.091758 1.145730 2.220446 +-3.404215 1.145730 2.220446 +-3.091758 0.876996 1.951714 +-3.404215 0.876996 1.951714 +-3.091758 0.704461 1.613092 +-3.404215 0.704461 1.613092 +-3.091758 0.645010 1.237725 +-3.404215 0.645010 1.237725 +-3.091758 0.704461 0.862359 +-3.404215 0.704461 0.862359 +-3.091758 0.876996 0.523737 +-3.404215 0.876996 0.523737 +-3.091758 1.145728 0.255004 +-3.404215 1.145728 0.255004 +-3.091758 1.484351 0.082466 +-3.404214 1.484348 0.082459 +-3.091758 1.859718 0.023011 +-3.404213 1.859718 0.022998 +-3.091758 2.235082 0.082466 +-3.404214 2.235084 0.082460 +-3.091758 2.573705 0.255005 +-3.404215 2.573705 0.255005 +-3.091758 2.842437 0.523737 +-3.404215 2.842437 0.523737 +-3.091758 3.014974 0.862359 +-3.404215 3.014974 0.862359 +-3.091758 3.074427 1.237726 +-3.404215 3.074427 1.237726 +-3.091758 3.014974 1.613092 +-3.404215 3.014974 1.613092 +-3.091758 2.842437 1.951714 +-3.404215 2.842437 1.951714 +-3.618763 1.859718 1.237716 +-3.614687 1.521825 0.197774 +-3.618766 1.529129 0.220249 +-3.614683 1.217003 0.353102 +-3.618762 1.230894 0.372220 +-3.614681 0.975093 0.595011 +-3.618760 0.994212 0.608901 +-3.614681 0.819783 0.899831 +-3.618761 0.842257 0.907133 +-3.614681 0.766266 1.237727 +-3.618761 0.789899 1.237727 +-3.614681 0.819783 1.575625 +-3.618761 0.842257 1.568322 +-3.614681 0.975093 1.880443 +-3.618761 0.994212 1.866553 +-3.614681 1.217003 2.122350 +-3.618761 1.230894 2.103232 +-3.614681 1.521820 2.277662 +-3.618761 1.529124 2.255188 +-3.614681 1.859718 2.331181 +-3.618761 1.859718 2.307549 +-3.614681 2.197613 2.277663 +-3.618761 2.190310 2.255188 +-3.614681 2.502431 2.122349 +-3.618761 2.488542 2.103231 +-3.614681 2.744338 1.880443 +-3.618761 2.725218 1.866552 +-3.614681 2.899651 1.575623 +-3.618760 2.877177 1.568321 +-3.614681 2.953170 1.237728 +-3.618761 2.929538 1.237728 +-3.614681 2.899651 0.899832 +-3.618761 2.877177 0.907135 +-3.614681 2.744338 0.595012 +-3.618761 2.725218 0.608902 +-3.614683 2.502429 0.353103 +-3.618762 2.488539 0.372221 +-3.614688 2.197606 0.197775 +-3.618767 2.190301 0.220249 +-3.614690 1.859718 0.144244 +-3.618771 1.859718 0.167876 +-2.738879 -1.419687 -0.116527 +-2.738879 -1.022734 0.085728 +-2.738879 -0.707714 0.400750 +-2.738879 -0.505456 0.797701 +-2.738879 -0.435763 1.237724 +-2.738879 -0.505456 1.677748 +-2.738879 -0.707714 2.074699 +-2.738879 -1.022734 2.389719 +-2.738879 -1.419687 2.591976 +-2.738879 -1.859709 2.661669 +-2.738879 -2.299730 2.591976 +-2.738879 -2.696681 2.389719 +-2.738879 -3.011703 2.074699 +-2.738879 -3.213958 1.677748 +-2.738879 -3.283651 1.237724 +-2.738879 -3.213958 0.797701 +-2.738879 -3.011703 0.400751 +-2.738879 -2.696681 0.085730 +-2.738879 -2.299730 -0.116527 +-2.738879 -1.859709 -0.186219 +-2.935497 -1.419687 -0.116527 +-2.935497 -1.022734 0.085728 +-2.935497 -0.707714 0.400750 +-2.935497 -0.505456 0.797701 +-2.935497 -0.435763 1.237724 +-2.935497 -0.505456 1.677748 +-2.935497 -0.707714 2.074699 +-2.935497 -1.022734 2.389719 +-2.935497 -1.419687 2.591976 +-2.935497 -1.859709 2.661669 +-2.935497 -2.299730 2.591976 +-2.935497 -2.696681 2.389719 +-2.935497 -3.011703 2.074699 +-2.935497 -3.213958 1.677748 +-2.935497 -3.283651 1.237724 +-2.935497 -3.213958 0.797701 +-2.935497 -3.011703 0.400751 +-2.935497 -2.696681 0.085730 +-2.935497 -2.299730 -0.116527 +-2.935475 -1.859709 -0.186219 +-2.935497 -1.474777 0.053035 +-2.935497 -1.127528 0.229966 +-2.935497 -0.851948 0.505546 +-2.935497 -0.675018 0.852796 +-2.935497 -0.614052 1.237725 +-2.935497 -0.675018 1.622655 +-2.935497 -0.851948 1.969905 +-2.935497 -1.127529 2.245484 +-2.935497 -1.474777 2.422416 +-2.935497 -1.859709 2.483384 +-2.935497 -2.244639 2.422416 +-2.935497 -2.591887 2.245484 +-2.935497 -2.867465 1.969905 +-2.935497 -3.044398 1.622655 +-2.935497 -3.105366 1.237726 +-2.935497 -3.044398 0.852796 +-2.935497 -2.867465 0.505546 +-2.935497 -2.591887 0.229967 +-2.935497 -2.244636 0.053036 +-2.935497 -1.859709 -0.007931 +-3.560476 -1.474776 0.053022 +-3.560476 -1.127528 0.229966 +-3.560476 -0.851948 0.505546 +-3.560476 -0.675018 0.852796 +-3.560476 -0.614052 1.237725 +-3.560476 -0.675018 1.622655 +-3.560476 -0.851948 1.969905 +-3.560476 -1.127529 2.245484 +-3.560476 -1.474777 2.422416 +-3.560476 -1.859709 2.483384 +-3.560476 -2.244639 2.422416 +-3.560476 -2.591887 2.245484 +-3.560476 -2.867465 1.969905 +-3.560476 -3.044398 1.622655 +-3.560476 -3.105366 1.237726 +-3.560476 -3.044398 0.852796 +-3.560476 -2.867465 0.505546 +-3.560476 -2.591887 0.229967 +-3.560476 -2.244639 0.053023 +-3.560476 -1.859709 -0.007957 +-3.404215 -2.573695 2.220446 +-3.091758 -2.573695 2.220446 +-3.091758 -2.235075 2.392983 +-3.404215 -2.235075 2.392982 +-3.091758 -1.859709 2.452435 +-3.404215 -1.859709 2.452435 +-3.091758 -1.484341 2.392983 +-3.404215 -1.484341 2.392982 +-3.091758 -1.145720 2.220446 +-3.404215 -1.145720 2.220446 +-3.091758 -0.876986 1.951714 +-3.404215 -0.876986 1.951714 +-3.091758 -0.704451 1.613092 +-3.404215 -0.704451 1.613092 +-3.091758 -0.645000 1.237725 +-3.404215 -0.645000 1.237725 +-3.091758 -0.704451 0.862359 +-3.404215 -0.704451 0.862359 +-3.091758 -0.876986 0.523737 +-3.404215 -0.876986 0.523737 +-3.091758 -1.145718 0.255004 +-3.404215 -1.145718 0.255004 +-3.091758 -1.484341 0.082466 +-3.404214 -1.484339 0.082459 +-3.091758 -1.859709 0.023011 +-3.404213 -1.859709 0.022998 +-3.091758 -2.235072 0.082466 +-3.404214 -2.235075 0.082460 +-3.091758 -2.573695 0.255005 +-3.404215 -2.573695 0.255005 +-3.091758 -2.842428 0.523737 +-3.404215 -2.842428 0.523737 +-3.091758 -3.014965 0.862359 +-3.404215 -3.014965 0.862359 +-3.091758 -3.074417 1.237726 +-3.404215 -3.074417 1.237726 +-3.091758 -3.014965 1.613092 +-3.404215 -3.014965 1.613092 +-3.091758 -2.842428 1.951714 +-3.404215 -2.842428 1.951714 +-3.618763 -1.859708 1.237716 +-3.614687 -1.521816 0.197774 +-3.618766 -1.529119 0.220249 +-3.614683 -1.216994 0.353102 +-3.618762 -1.230884 0.372220 +-3.614681 -0.975084 0.595011 +-3.618760 -0.994203 0.608901 +-3.614681 -0.819773 0.899831 +-3.618761 -0.842248 0.907133 +-3.614681 -0.766257 1.237727 +-3.618761 -0.789889 1.237727 +-3.614681 -0.819773 1.575625 +-3.618761 -0.842248 1.568322 +-3.614681 -0.975084 1.880443 +-3.618761 -0.994203 1.866553 +-3.614681 -1.216994 2.122350 +-3.618761 -1.230884 2.103232 +-3.614681 -1.521811 2.277662 +-3.618761 -1.529114 2.255188 +-3.614681 -1.859709 2.331181 +-3.618761 -1.859709 2.307549 +-3.614681 -2.197604 2.277663 +-3.618761 -2.190300 2.255188 +-3.614681 -2.502422 2.122349 +-3.618761 -2.488533 2.103231 +-3.614681 -2.744328 1.880443 +-3.618761 -2.725209 1.866552 +-3.614681 -2.899642 1.575623 +-3.618760 -2.877167 1.568321 +-3.614681 -2.953161 1.237728 +-3.618761 -2.929529 1.237728 +-3.614681 -2.899642 0.899832 +-3.618761 -2.877167 0.907135 +-3.614681 -2.744328 0.595012 +-3.618761 -2.725209 0.608902 +-3.614683 -2.502419 0.353103 +-3.618762 -2.488530 0.372221 +-3.614688 -2.197596 0.197775 +-3.618767 -2.190292 0.220249 +-3.614690 -1.859708 0.144244 +-3.618771 -1.859708 0.167876 +2.738880 1.419696 -0.116527 +2.738880 1.022744 0.085728 +2.738880 0.707723 0.400750 +2.738880 0.505466 0.797701 +2.738880 0.435773 1.237724 +2.738880 0.505466 1.677748 +2.738880 0.707723 2.074699 +2.738880 1.022744 2.389719 +2.738880 1.419696 2.591976 +2.738880 1.859718 2.661669 +2.738880 2.299739 2.591976 +2.738880 2.696691 2.389719 +2.738880 3.011713 2.074699 +2.738880 3.213968 1.677748 +2.738880 3.283660 1.237724 +2.738880 3.213968 0.797701 +2.738880 3.011713 0.400751 +2.738880 2.696691 0.085730 +2.738880 2.299739 -0.116527 +2.738880 1.859718 -0.186219 +2.935498 1.419696 -0.116527 +2.935498 1.022744 0.085728 +2.935498 0.707723 0.400750 +2.935498 0.505466 0.797701 +2.935498 0.435773 1.237724 +2.935498 0.505466 1.677748 +2.935498 0.707723 2.074699 +2.935498 1.022744 2.389719 +2.935498 1.419696 2.591976 +2.935498 1.859718 2.661669 +2.935498 2.299739 2.591976 +2.935498 2.696691 2.389719 +2.935498 3.011713 2.074699 +2.935498 3.213968 1.677748 +2.935498 3.283660 1.237724 +2.935498 3.213968 0.797701 +2.935498 3.011713 0.400751 +2.935498 2.696691 0.085730 +2.935498 2.299739 -0.116527 +2.935476 1.859718 -0.186219 +2.935498 1.474786 0.053035 +2.935498 1.127537 0.229966 +2.935498 0.851958 0.505546 +2.935498 0.675027 0.852796 +2.935498 0.614061 1.237725 +2.935498 0.675027 1.622655 +2.935498 0.851958 1.969905 +2.935498 1.127539 2.245484 +2.935498 1.474786 2.422416 +2.935498 1.859718 2.483384 +2.935498 2.244648 2.422416 +2.935498 2.591897 2.245484 +2.935498 2.867475 1.969905 +2.935498 3.044407 1.622655 +2.935498 3.105376 1.237726 +2.935498 3.044407 0.852796 +2.935498 2.867475 0.505546 +2.935498 2.591897 0.229967 +2.935498 2.244646 0.053036 +2.935498 1.859718 -0.007931 +3.560477 1.474785 0.053022 +3.560477 1.127537 0.229966 +3.560477 0.851958 0.505546 +3.560477 0.675027 0.852796 +3.560477 0.614061 1.237725 +3.560477 0.675027 1.622655 +3.560477 0.851958 1.969905 +3.560477 1.127539 2.245484 +3.560477 1.474786 2.422416 +3.560477 1.859718 2.483384 +3.560477 2.244648 2.422416 +3.560477 2.591897 2.245484 +3.560477 2.867475 1.969905 +3.560477 3.044407 1.622655 +3.560477 3.105376 1.237726 +3.560477 3.044407 0.852796 +3.560477 2.867475 0.505546 +3.560477 2.591897 0.229967 +3.560477 2.244648 0.053023 +3.560477 1.859718 -0.007957 +3.404215 2.573705 2.220446 +3.091759 2.573705 2.220446 +3.091759 2.235084 2.392983 +3.404215 2.235084 2.392982 +3.091759 1.859718 2.452435 +3.404215 1.859718 2.452435 +3.091759 1.484351 2.392983 +3.404215 1.484351 2.392982 +3.091759 1.145730 2.220446 +3.404215 1.145730 2.220446 +3.091759 0.876996 1.951714 +3.404215 0.876996 1.951714 +3.091759 0.704461 1.613092 +3.404215 0.704461 1.613092 +3.091759 0.645010 1.237725 +3.404215 0.645010 1.237725 +3.091759 0.704461 0.862359 +3.404215 0.704461 0.862359 +3.091759 0.876996 0.523737 +3.404215 0.876996 0.523737 +3.091759 1.145728 0.255004 +3.404215 1.145728 0.255004 +3.091758 1.484351 0.082466 +3.404214 1.484348 0.082459 +3.091758 1.859718 0.023011 +3.404214 1.859718 0.022998 +3.091758 2.235082 0.082466 +3.404214 2.235084 0.082460 +3.091759 2.573705 0.255005 +3.404215 2.573705 0.255005 +3.091759 2.842437 0.523737 +3.404215 2.842437 0.523737 +3.091759 3.014974 0.862359 +3.404215 3.014974 0.862359 +3.091759 3.074427 1.237726 +3.404215 3.074427 1.237726 +3.091759 3.014974 1.613092 +3.404215 3.014974 1.613092 +3.091759 2.842437 1.951714 +3.404215 2.842437 1.951714 +3.618764 1.859718 1.237716 +3.614688 1.521825 0.197774 +3.618767 1.529129 0.220249 +3.614683 1.217003 0.353102 +3.618762 1.230894 0.372220 +3.614682 0.975093 0.595011 +3.618761 0.994212 0.608901 +3.614682 0.819783 0.899831 +3.618762 0.842257 0.907133 +3.614682 0.766266 1.237727 +3.618762 0.789899 1.237727 +3.614682 0.819783 1.575625 +3.618762 0.842257 1.568322 +3.614682 0.975093 1.880443 +3.618762 0.994212 1.866553 +3.614682 1.217003 2.122350 +3.618762 1.230894 2.103232 +3.614682 1.521820 2.277662 +3.618762 1.529124 2.255188 +3.614682 1.859718 2.331181 +3.618762 1.859718 2.307549 +3.614682 2.197613 2.277663 +3.618762 2.190310 2.255188 +3.614682 2.502431 2.122349 +3.618762 2.488542 2.103231 +3.614682 2.744338 1.880443 +3.618762 2.725218 1.866552 +3.614682 2.899651 1.575623 +3.618761 2.877177 1.568321 +3.614682 2.953170 1.237728 +3.618762 2.929538 1.237728 +3.614682 2.899651 0.899832 +3.618762 2.877177 0.907135 +3.614682 2.744338 0.595012 +3.618762 2.725218 0.608902 +3.614683 2.502429 0.353103 +3.618763 2.488539 0.372221 +3.614688 2.197606 0.197775 +3.618768 2.190301 0.220249 +3.614691 1.859718 0.144244 +3.618771 1.859718 0.167876 +2.738880 -1.419687 -0.116527 +2.738880 -1.022734 0.085728 +2.738880 -0.707714 0.400750 +2.738880 -0.505456 0.797701 +2.738880 -0.435763 1.237724 +2.738880 -0.505456 1.677748 +2.738880 -0.707714 2.074699 +2.738880 -1.022734 2.389719 +2.738880 -1.419687 2.591976 +2.738880 -1.859709 2.661669 +2.738880 -2.299730 2.591976 +2.738880 -2.696681 2.389719 +2.738880 -3.011703 2.074699 +2.738880 -3.213958 1.677748 +2.738880 -3.283651 1.237724 +2.738880 -3.213958 0.797701 +2.738880 -3.011703 0.400751 +2.738880 -2.696681 0.085730 +2.738880 -2.299730 -0.116527 +2.738880 -1.859709 -0.186219 +2.935498 -1.419687 -0.116527 +2.935498 -1.022734 0.085728 +2.935498 -0.707714 0.400750 +2.935498 -0.505456 0.797701 +2.935498 -0.435763 1.237724 +2.935498 -0.505456 1.677748 +2.935498 -0.707714 2.074699 +2.935498 -1.022734 2.389719 +2.935498 -1.419687 2.591976 +2.935498 -1.859709 2.661669 +2.935498 -2.299730 2.591976 +2.935498 -2.696681 2.389719 +2.935498 -3.011703 2.074699 +2.935498 -3.213958 1.677748 +2.935498 -3.283651 1.237724 +2.935498 -3.213958 0.797701 +2.935498 -3.011703 0.400751 +2.935498 -2.696681 0.085730 +2.935498 -2.299730 -0.116527 +2.935476 -1.859709 -0.186219 +2.935498 -1.474777 0.053035 +2.935498 -1.127528 0.229966 +2.935498 -0.851948 0.505546 +2.935498 -0.675018 0.852796 +2.935498 -0.614052 1.237725 +2.935498 -0.675018 1.622655 +2.935498 -0.851948 1.969905 +2.935498 -1.127529 2.245484 +2.935498 -1.474777 2.422416 +2.935498 -1.859709 2.483384 +2.935498 -2.244639 2.422416 +2.935498 -2.591887 2.245484 +2.935498 -2.867465 1.969905 +2.935498 -3.044398 1.622655 +2.935498 -3.105366 1.237726 +2.935498 -3.044398 0.852796 +2.935498 -2.867465 0.505546 +2.935498 -2.591887 0.229967 +2.935498 -2.244636 0.053036 +2.935498 -1.859709 -0.007931 +3.560477 -1.474776 0.053022 +3.560477 -1.127528 0.229966 +3.560477 -0.851948 0.505546 +3.560477 -0.675018 0.852796 +3.560477 -0.614052 1.237725 +3.560477 -0.675018 1.622655 +3.560477 -0.851948 1.969905 +3.560477 -1.127529 2.245484 +3.560477 -1.474777 2.422416 +3.560477 -1.859709 2.483384 +3.560477 -2.244639 2.422416 +3.560477 -2.591887 2.245484 +3.560477 -2.867465 1.969905 +3.560477 -3.044398 1.622655 +3.560477 -3.105366 1.237726 +3.560477 -3.044398 0.852796 +3.560477 -2.867465 0.505546 +3.560477 -2.591887 0.229967 +3.560477 -2.244639 0.053023 +3.560477 -1.859709 -0.007957 +3.404215 -2.573695 2.220446 +3.091759 -2.573695 2.220446 +3.091759 -2.235075 2.392983 +3.404215 -2.235075 2.392982 +3.091759 -1.859709 2.452435 +3.404215 -1.859709 2.452435 +3.091759 -1.484341 2.392983 +3.404215 -1.484341 2.392982 +3.091759 -1.145720 2.220446 +3.404215 -1.145720 2.220446 +3.091759 -0.876986 1.951714 +3.404215 -0.876986 1.951714 +3.091759 -0.704451 1.613092 +3.404215 -0.704451 1.613092 +3.091759 -0.645000 1.237725 +3.404215 -0.645000 1.237725 +3.091759 -0.704451 0.862359 +3.404215 -0.704451 0.862359 +3.091759 -0.876986 0.523737 +3.404215 -0.876986 0.523737 +3.091759 -1.145718 0.255004 +3.404215 -1.145718 0.255004 +3.091758 -1.484341 0.082466 +3.404214 -1.484339 0.082459 +3.091758 -1.859709 0.023011 +3.404214 -1.859709 0.022998 +3.091758 -2.235072 0.082466 +3.404214 -2.235075 0.082460 +3.091759 -2.573695 0.255005 +3.404215 -2.573695 0.255005 +3.091759 -2.842428 0.523737 +3.404215 -2.842428 0.523737 +3.091759 -3.014965 0.862359 +3.404215 -3.014965 0.862359 +3.091759 -3.074417 1.237726 +3.404215 -3.074417 1.237726 +3.091759 -3.014965 1.613092 +3.404215 -3.014965 1.613092 +3.091759 -2.842428 1.951714 +3.404215 -2.842428 1.951714 +3.618764 -1.859708 1.237716 +3.614688 -1.521816 0.197774 +3.618767 -1.529119 0.220249 +3.614683 -1.216994 0.353102 +3.618762 -1.230884 0.372220 +3.614682 -0.975084 0.595011 +3.618761 -0.994203 0.608901 +3.614682 -0.819773 0.899831 +3.618762 -0.842248 0.907133 +3.614682 -0.766257 1.237727 +3.618762 -0.789889 1.237727 +3.614682 -0.819773 1.575625 +3.618762 -0.842248 1.568322 +3.614682 -0.975084 1.880443 +3.618762 -0.994203 1.866553 +3.614682 -1.216994 2.122350 +3.618762 -1.230884 2.103232 +3.614682 -1.521811 2.277662 +3.618762 -1.529114 2.255188 +3.614682 -1.859709 2.331181 +3.618762 -1.859709 2.307549 +3.614682 -2.197604 2.277663 +3.618762 -2.190300 2.255188 +3.614682 -2.502422 2.122349 +3.618762 -2.488533 2.103231 +3.614682 -2.744328 1.880443 +3.618762 -2.725209 1.866552 +3.614682 -2.899642 1.575623 +3.618761 -2.877167 1.568321 +3.614682 -2.953161 1.237728 +3.618762 -2.929529 1.237728 +3.614682 -2.899642 0.899832 +3.618762 -2.877167 0.907135 +3.614682 -2.744328 0.595012 +3.618762 -2.725209 0.608902 +3.614683 -2.502419 0.353103 +3.618763 -2.488530 0.372221 +3.614688 -2.197596 0.197775 +3.618768 -2.190292 0.220249 +3.614691 -1.859708 0.144244 +3.618771 -1.859708 0.167876 +-3.192152 3.560921 2.141005 +-3.192152 3.482032 2.083689 +-3.192152 3.384521 2.083689 +-3.192152 3.305632 2.141005 +-3.192152 3.275500 2.233744 +-3.192152 3.305632 2.326483 +-3.192152 3.384521 2.383799 +-3.192152 3.482032 2.383799 +-3.192152 3.560921 2.326483 +-3.192152 3.591053 2.233744 +-3.349929 3.560921 2.141005 +-3.349929 3.482032 2.083689 +-3.349929 3.384521 2.083689 +-3.349929 3.305632 2.141005 +-3.349929 3.275500 2.233744 +-3.349929 3.305632 2.326483 +-3.349929 3.384521 2.383799 +-3.349929 3.482032 2.383799 +-3.349929 3.560921 2.326483 +-3.349929 3.591053 2.233744 +-3.356611 3.147122 1.880422 +-3.136376 3.147122 1.880422 +-3.356611 3.719431 1.880422 +-3.356611 3.367182 2.030326 +-3.356611 3.260238 2.108025 +-3.139046 3.267993 2.113659 +-3.139046 3.370144 2.039443 +-3.356611 3.219389 2.233744 +-3.139046 3.228976 2.233744 +-3.356611 3.147122 2.233744 +-3.356611 3.260238 2.359464 +-3.139046 3.267993 2.353829 +-3.356611 3.606315 2.108025 +-3.356611 3.499371 2.030326 +-3.139046 3.496409 2.039443 +-3.139046 3.598560 2.113659 +-3.136376 3.719431 1.880422 +-3.356611 3.367182 2.437163 +-3.139046 3.370144 2.428046 +-3.356611 3.647164 2.233744 +-3.139046 3.637578 2.233744 +-3.136376 3.147122 2.587066 +-3.356611 3.147122 2.587066 +-3.356611 3.606315 2.359464 +-3.139046 3.598560 2.353829 +-3.356611 3.499371 2.437163 +-3.139046 3.496409 2.428046 +-3.356611 3.719431 2.233744 +-3.356611 3.719431 2.587066 +-3.136376 3.719431 2.587066 +-3.349929 3.497476 2.187101 +-3.349929 3.457798 2.158274 +-3.349929 3.408755 2.158274 +-3.349929 3.369077 2.187101 +-3.349929 3.353922 2.233744 +-3.349929 3.369077 2.280388 +-3.349929 3.408755 2.309214 +-3.349929 3.457798 2.309214 +-3.349929 3.497476 2.280388 +-3.349929 3.512631 2.233744 +-3.374013 3.456987 2.201111 +-3.374013 3.409566 2.201111 +-3.374013 3.390864 2.233744 +-3.374013 3.409566 2.266377 +-3.374013 3.456987 2.266377 +-3.374013 3.475689 2.233744 +-3.192152 3.560921 1.619839 +-3.192152 3.482032 1.677155 +-3.192152 3.384521 1.677155 +-3.192152 3.305632 1.619839 +-3.192152 3.275500 1.527100 +-3.192152 3.305632 1.434361 +-3.192152 3.384521 1.377045 +-3.192152 3.482032 1.377045 +-3.192152 3.560921 1.434361 +-3.192152 3.591053 1.527100 +-3.349929 3.560921 1.619839 +-3.349929 3.482032 1.677155 +-3.349929 3.384521 1.677155 +-3.349929 3.305632 1.619839 +-3.349929 3.275500 1.527100 +-3.349929 3.305632 1.434361 +-3.349929 3.384521 1.377045 +-3.349929 3.482032 1.377045 +-3.349929 3.560921 1.434361 +-3.349929 3.591053 1.527100 +-3.356611 3.367182 1.730519 +-3.356611 3.260238 1.652820 +-3.139046 3.267993 1.647185 +-3.139046 3.370144 1.721402 +-3.356611 3.219389 1.527100 +-3.139046 3.228976 1.527100 +-3.356611 3.147122 1.527100 +-3.356611 3.260238 1.401381 +-3.139046 3.267993 1.407015 +-3.356611 3.606315 1.652820 +-3.356611 3.499371 1.730519 +-3.139046 3.496409 1.721402 +-3.139046 3.598560 1.647185 +-3.356611 3.367182 1.323682 +-3.139046 3.370144 1.332799 +-3.356611 3.647164 1.527100 +-3.139046 3.637578 1.527100 +-3.136376 3.147122 1.173778 +-3.356611 3.147122 1.173778 +-3.356611 3.606315 1.401381 +-3.139046 3.598560 1.407015 +-3.356611 3.499371 1.323682 +-3.139046 3.496409 1.332799 +-3.356611 3.719431 1.527100 +-3.356611 3.719431 1.173778 +-3.136376 3.719431 1.173778 +-3.349929 3.497476 1.573743 +-3.349929 3.457798 1.602570 +-3.349929 3.408755 1.602570 +-3.349929 3.369077 1.573743 +-3.349929 3.353922 1.527100 +-3.349929 3.369077 1.480457 +-3.349929 3.408755 1.451630 +-3.349929 3.457798 1.451630 +-3.349929 3.497476 1.480457 +-3.349929 3.512631 1.527100 +-3.374013 3.456987 1.559733 +-3.374013 3.409566 1.559733 +-3.374013 3.390864 1.527100 +-3.374013 3.409566 1.494467 +-3.374013 3.456987 1.494467 +-3.374013 3.475689 1.527100 +3.192152 3.560921 2.141005 +3.192152 3.482032 2.083689 +3.192152 3.384521 2.083689 +3.192152 3.305632 2.141005 +3.192152 3.275500 2.233744 +3.192152 3.305632 2.326483 +3.192152 3.384521 2.383799 +3.192152 3.482032 2.383799 +3.192152 3.560921 2.326483 +3.192152 3.591053 2.233744 +3.349929 3.560921 2.141005 +3.349929 3.482032 2.083689 +3.349929 3.384521 2.083689 +3.349929 3.305632 2.141005 +3.349929 3.275500 2.233744 +3.349929 3.305632 2.326483 +3.349929 3.384521 2.383799 +3.349929 3.482032 2.383799 +3.349929 3.560921 2.326483 +3.349929 3.591053 2.233744 +3.356612 3.147122 1.880422 +3.136376 3.147122 1.880422 +3.356612 3.719431 1.880422 +3.356612 3.367182 2.030326 +3.356612 3.260238 2.108025 +3.139046 3.267993 2.113659 +3.139046 3.370144 2.039443 +3.356612 3.219389 2.233744 +3.139046 3.228976 2.233744 +3.356612 3.147122 2.233744 +3.356612 3.260238 2.359464 +3.139046 3.267993 2.353829 +3.356612 3.606315 2.108025 +3.356612 3.499371 2.030326 +3.139046 3.496409 2.039443 +3.139046 3.598560 2.113659 +3.136376 3.719431 1.880422 +3.356612 3.367182 2.437163 +3.139046 3.370144 2.428046 +3.356612 3.647164 2.233744 +3.139046 3.637578 2.233744 +3.136376 3.147122 2.587066 +3.356612 3.147122 2.587066 +3.356612 3.606315 2.359464 +3.139046 3.598560 2.353829 +3.356612 3.499371 2.437163 +3.139046 3.496409 2.428046 +3.356612 3.719431 2.233744 +3.356612 3.719431 2.587066 +3.136376 3.719431 2.587066 +3.349929 3.497476 2.187101 +3.349929 3.457798 2.158274 +3.349929 3.408755 2.158274 +3.349929 3.369077 2.187101 +3.349929 3.353922 2.233744 +3.349929 3.369077 2.280388 +3.349929 3.408755 2.309214 +3.349929 3.457798 2.309214 +3.349929 3.497476 2.280388 +3.349929 3.512631 2.233744 +3.374014 3.456987 2.201111 +3.374014 3.409566 2.201111 +3.374014 3.390864 2.233744 +3.374014 3.409566 2.266377 +3.374014 3.456987 2.266377 +3.374014 3.475689 2.233744 +3.192152 3.560921 1.619839 +3.192152 3.482032 1.677155 +3.192152 3.384521 1.677155 +3.192152 3.305632 1.619839 +3.192152 3.275500 1.527100 +3.192152 3.305632 1.434361 +3.192152 3.384521 1.377045 +3.192152 3.482032 1.377045 +3.192152 3.560921 1.434361 +3.192152 3.591053 1.527100 +3.349929 3.560921 1.619839 +3.349929 3.482032 1.677155 +3.349929 3.384521 1.677155 +3.349929 3.305632 1.619839 +3.349929 3.275500 1.527100 +3.349929 3.305632 1.434361 +3.349929 3.384521 1.377045 +3.349929 3.482032 1.377045 +3.349929 3.560921 1.434361 +3.349929 3.591053 1.527100 +3.356612 3.367182 1.730519 +3.356612 3.260238 1.652820 +3.139046 3.267993 1.647185 +3.139046 3.370144 1.721402 +3.356612 3.219389 1.527100 +3.139046 3.228976 1.527100 +3.356612 3.147122 1.527100 +3.356612 3.260238 1.401381 +3.139046 3.267993 1.407015 +3.356612 3.606315 1.652820 +3.356612 3.499371 1.730519 +3.139046 3.496409 1.721402 +3.139046 3.598560 1.647185 +3.356612 3.367182 1.323682 +3.139046 3.370144 1.332799 +3.356612 3.647164 1.527100 +3.139046 3.637578 1.527100 +3.136376 3.147122 1.173778 +3.356612 3.147122 1.173778 +3.356612 3.606315 1.401381 +3.139046 3.598560 1.407015 +3.356612 3.499371 1.323682 +3.139046 3.496409 1.332799 +3.356612 3.719431 1.527100 +3.356612 3.719431 1.173778 +3.136376 3.719431 1.173778 +3.349929 3.497476 1.573743 +3.349929 3.457798 1.602570 +3.349929 3.408755 1.602570 +3.349929 3.369077 1.573743 +3.349929 3.353922 1.527100 +3.349929 3.369077 1.480457 +3.349929 3.408755 1.451630 +3.349929 3.457798 1.451630 +3.349929 3.497476 1.480457 +3.349929 3.512631 1.527100 +3.374014 3.456987 1.559733 +3.374014 3.409566 1.559733 +3.374014 3.390864 1.527100 +3.374014 3.409566 1.494467 +3.374014 3.456987 1.494467 +3.374014 3.475689 1.527100 +-3.356611 -2.675469 3.902446 +-3.356611 -2.839080 3.834677 +-3.356611 -3.002690 3.902446 +-3.356611 -3.070460 4.066057 +-3.356611 -3.002690 4.229667 +-3.356611 -2.839080 4.297437 +-3.356611 -2.675469 4.229667 +-3.356611 -2.607699 4.066057 +-3.092774 -2.675469 3.902446 +-3.092774 -2.839080 3.834677 +-3.092774 -3.002690 3.902446 +-3.092774 -3.070460 4.066057 +-3.092774 -3.002690 4.229667 +-3.092774 -2.839080 4.297437 +-3.092774 -2.675469 4.229667 +-3.092774 -2.607699 4.066057 +-3.356611 -5.821976 2.587066 +-3.356611 3.915582 2.587066 +-3.356611 -5.821976 0.079790 +-3.356611 -3.915574 2.587066 +-3.356611 -3.915574 0.079790 +-3.356611 -3.915574 5.156613 +-3.356611 3.915582 5.156613 +-2.063218 -3.915574 7.038242 +-2.284143 -3.915574 6.911219 +-2.448534 -3.915574 6.716492 +-1.812224 -3.915574 7.082344 +-2.284143 3.915582 6.911219 +-2.063218 3.915582 7.038242 +-1.812224 3.915582 7.082344 +-2.448534 3.915582 6.716492 +-3.236611 -4.035573 2.587066 +-3.236611 -5.701976 2.587066 +-3.236611 -4.035573 0.870267 +-3.236611 -5.701976 0.870267 +-1.812224 -3.719422 7.082344 +-1.812224 3.719430 7.082344 +-2.063218 -3.719422 7.038242 +-2.063218 3.719430 7.038242 +-2.284143 -3.719422 6.911219 +-2.284143 3.719430 6.911219 +-2.448534 -3.719422 6.716492 +-2.448534 3.719430 6.716492 +-3.356611 -3.719422 5.156613 +-3.356611 3.719430 5.156613 +-3.356611 -3.719422 2.587066 +-3.356611 3.719430 2.587066 +-3.356611 -3.719422 0.079790 +-2.738879 3.719430 2.587066 +-2.738879 -3.719422 2.587066 +0.000000 3.915582 7.082344 +0.000000 3.719430 7.082344 +0.000000 -3.719422 7.082344 +0.000000 -3.915574 7.082344 +0.000000 -4.035573 0.870267 +0.000000 -5.701976 0.870267 +0.000000 -5.701976 2.587066 +0.000000 -5.821976 2.587066 +0.000000 -5.821976 0.079790 +0.000000 -3.915574 0.079790 +0.000000 -3.719422 0.079790 +0.000000 3.719430 0.222106 +0.000000 3.915582 0.222106 +0.000000 3.915582 3.708995 +-2.738879 -3.719422 0.531430 +-2.738879 3.719430 0.531430 +0.000000 3.719430 0.531430 +0.000000 -3.719422 0.531430 +-3.190536 3.915582 0.222106 +-3.307969 3.915582 0.270749 +-3.356611 3.915582 0.388181 +-3.356611 3.719430 0.388181 +-3.307969 3.719430 0.270749 +-3.190536 3.719430 0.222106 +-3.356611 -3.915574 4.830924 +-3.356611 3.915582 4.830924 +-3.356611 3.719430 4.830924 +-3.356611 -3.719422 4.830924 +-3.356611 -3.915574 2.880850 +-3.356611 3.915582 2.880850 +-3.356611 3.719430 2.880850 +-3.356611 -3.719422 2.880850 +-3.356611 0.000004 2.587066 +-3.356611 0.000004 2.880850 +-3.356611 0.000004 4.830924 +-3.356611 0.000004 5.156613 +-2.448534 0.000004 6.716492 +-2.284143 0.000004 6.911219 +-2.063218 0.000004 7.038242 +-1.812224 0.000004 7.082344 +0.000000 0.000004 7.082344 +0.000000 0.000004 0.531430 +-2.738879 0.000004 0.531430 +-2.738879 0.000004 2.587066 +-3.356611 3.297849 4.645667 +-3.356611 3.297849 3.066107 +-3.356611 0.996729 3.066107 +-3.356611 0.996729 4.645667 +-2.498844 3.619430 6.630069 +-3.306301 3.619430 5.243036 +-3.306301 0.000004 5.243036 +-2.498844 0.000004 6.630069 +-3.306301 -3.619422 5.243036 +-2.498844 -3.619422 6.630069 +-2.421064 3.619430 6.584790 +-3.228520 3.619430 5.197756 +-3.228520 0.000004 5.197756 +-2.421064 0.000004 6.584790 +-3.228520 -3.619422 5.197756 +-2.421064 -3.619422 6.584790 +-3.266611 3.297849 4.645667 +-3.266611 3.297849 3.066107 +-3.266611 0.996729 3.066107 +-3.266611 0.996729 4.645667 +-3.266611 3.209301 4.116412 +-3.266611 3.209301 3.595362 +-3.266611 3.109516 3.595362 +-3.266611 3.109516 4.116412 +-3.228477 3.209301 4.116412 +-3.228477 3.209301 3.595362 +-3.228477 3.109516 3.595362 +-3.228477 3.109516 4.116412 +3.356612 -5.821976 2.587066 +3.356612 3.915582 2.587066 +3.356612 -5.821976 0.079790 +3.356612 -3.915574 2.587066 +3.356612 -3.915574 0.079790 +3.356612 -3.915574 5.156613 +3.356612 3.915582 5.156613 +2.063219 -3.915574 7.038242 +2.284144 -3.915574 6.911219 +2.448534 -3.915574 6.716492 +1.812225 -3.915574 7.082344 +2.284144 3.915582 6.911219 +2.063219 3.915582 7.038242 +1.812225 3.915582 7.082344 +2.448534 3.915582 6.716492 +3.236612 -4.035573 2.587066 +3.236612 -5.701976 2.587066 +3.236612 -4.035573 0.870267 +3.236612 -5.701976 0.870267 +1.812225 -3.719422 7.082344 +1.812225 3.719430 7.082344 +2.063219 -3.719422 7.038242 +2.063219 3.719430 7.038242 +2.284144 -3.719422 6.911219 +2.284144 3.719430 6.911219 +2.448534 -3.719422 6.716492 +2.448534 3.719430 6.716492 +3.356612 -3.719422 5.156613 +3.356612 3.719430 5.156613 +3.356612 -3.719422 2.587066 +3.356612 3.719430 2.587066 +3.356612 -3.719422 0.079790 +2.738880 3.719430 2.587066 +2.738880 -3.719422 2.587066 +2.738880 -3.719422 0.531430 +2.738880 3.719430 0.531430 +3.190537 3.915582 0.222106 +3.307970 3.915582 0.270749 +3.356612 3.915582 0.388181 +3.356612 3.719430 0.388181 +3.307970 3.719430 0.270749 +3.190537 3.719430 0.222106 +3.356612 -3.915574 4.830924 +3.356612 3.915582 4.830924 +3.356612 3.719430 4.830924 +3.356612 -3.719422 4.830924 +3.356612 -3.915574 2.880850 +3.356612 3.915582 2.880850 +3.356612 3.719430 2.880850 +3.356612 -3.719422 2.880850 +3.356612 0.000004 2.587066 +3.356612 0.000004 2.880850 +3.356612 0.000004 4.830924 +3.356612 0.000004 5.156613 +2.448534 0.000004 6.716492 +2.284144 0.000004 6.911219 +2.063219 0.000004 7.038242 +1.812225 0.000004 7.082344 +2.738880 0.000004 0.531430 +2.738880 0.000004 2.587066 +3.356612 3.297849 4.645667 +3.356612 3.297849 3.066107 +3.356612 0.996729 3.066107 +3.356612 0.996729 4.645667 +2.498845 3.619430 6.630069 +3.306301 3.619430 5.243036 +3.306301 0.000004 5.243036 +2.498845 0.000004 6.630069 +3.306301 -3.619422 5.243036 +2.498845 -3.619422 6.630069 +2.421065 3.619430 6.584790 +3.228521 3.619430 5.197756 +3.228521 0.000004 5.197756 +2.421065 0.000004 6.584790 +3.228521 -3.619422 5.197756 +2.421065 -3.619422 6.584790 +3.266612 3.297849 4.645667 +3.266612 3.297849 3.066107 +3.266612 0.996729 3.066107 +3.266612 0.996729 4.645667 +3.266612 3.209301 4.116412 +3.266612 3.209301 3.595362 +3.266612 3.109516 3.595362 +3.266612 3.109516 4.116412 +3.228478 3.209301 4.116412 +3.228478 3.209301 3.595362 +3.228478 3.109516 3.595362 +3.228478 3.109516 4.116412 +-3.092774 -2.693636 3.920613 +-3.092774 -2.839080 3.860369 +-3.092774 -2.984523 3.920613 +-3.092774 -3.044768 4.066057 +-3.092774 -2.984523 4.211500 +-3.092774 -2.839080 4.271745 +-3.092774 -2.693636 4.211500 +-3.092774 -2.633391 4.066057 +-3.330009 -2.693636 3.920613 +-3.356611 -2.713996 3.940973 +-3.356611 -2.839080 3.889162 +-3.330009 -2.839080 3.860369 +-3.356611 -2.964163 3.940973 +-3.330009 -2.984523 3.920613 +-3.356611 -3.015975 4.066057 +-3.330009 -3.044768 4.066057 +-3.356611 -2.964163 4.191140 +-3.330009 -2.984523 4.211500 +-3.356611 -2.839080 4.242952 +-3.330009 -2.839080 4.271745 +-3.356611 -2.713996 4.191140 +-3.330009 -2.693636 4.211500 +-3.356611 -2.662185 4.066057 +-3.330009 -2.633391 4.066057 +-3.356611 -2.839080 4.066057 +0.000000 -4.035573 2.587066 +0.000000 -3.915574 2.587066 +-0.385505 4.370259 6.523432 +-0.866222 4.370259 7.126232 +-0.866222 4.370259 7.521652 +-0.385505 4.370259 8.124452 +0.000000 4.370259 8.212440 +0.000000 4.370259 6.435444 +-0.364798 4.531409 6.566432 +-0.819693 4.531409 7.136852 +-0.819694 4.531409 7.511032 +-0.364798 4.531409 8.081452 +0.000000 4.531409 8.164716 +0.000000 4.531409 6.483168 +-0.297576 4.531409 6.706018 +-0.668649 4.531409 7.171327 +-0.668649 4.531409 7.476558 +-0.297577 4.531409 7.941867 +0.000000 4.531409 8.009788 +0.000000 4.531409 6.638097 +-0.220988 4.155853 6.865055 +-0.496557 4.155853 7.210606 +-0.496557 4.155853 7.437279 +-0.220989 4.155853 7.782830 +0.000000 4.155853 7.833271 +0.000000 4.155853 6.814615 +-0.210654 4.593983 6.886514 +-0.473336 4.593983 7.215908 +-0.473336 4.593983 7.431977 +-0.210654 4.593983 7.761370 +0.000000 4.593983 7.809451 +0.000000 4.593983 6.838434 +-0.194826 4.680048 6.919381 +-0.437771 4.680048 7.224024 +-0.437771 4.680048 7.423861 +-0.194826 4.680048 7.728504 +0.000000 4.680048 7.772972 +0.000000 4.680048 6.874913 +-0.158925 4.680048 6.993929 +-0.357103 4.680048 7.242437 +-0.357103 4.680048 7.405450 +-0.158926 4.680048 7.653957 +0.000000 4.680048 7.690229 +0.000000 4.680048 6.957656 +-0.158925 4.593983 6.993929 +-0.357103 4.593983 7.242437 +-0.357103 4.593983 7.405450 +-0.158926 4.593983 7.653957 +0.000000 4.593983 7.690229 +0.000000 4.593983 6.957656 +-0.687283 4.370259 6.775852 +-0.687283 4.370259 7.872033 +-0.624210 4.531409 6.773306 +-0.675731 4.531409 6.837911 +-0.675731 4.531409 7.809974 +-0.624210 4.531409 7.874579 +-0.503081 4.531409 6.869902 +-0.554602 4.531409 6.934508 +-0.554602 4.531409 7.713378 +-0.503082 4.531409 7.777982 +-0.392732 4.155853 7.010749 +-0.392732 4.155853 7.637136 +-0.397973 4.593983 7.059415 +-0.346452 4.593983 6.994809 +-0.317932 4.680048 7.017554 +-0.369453 4.680048 7.082160 +-0.346452 4.593983 7.653075 +-0.397973 4.593983 7.588469 +-0.369453 4.680048 7.565724 +-0.317932 4.680048 7.630331 +-0.304762 4.680048 7.133748 +-0.253241 4.680048 7.069144 +-0.304762 4.593983 7.133748 +-0.253241 4.593983 7.069144 +-0.253241 4.680048 7.578742 +-0.304762 4.680048 7.514136 +-0.253241 4.593983 7.578742 +-0.304762 4.593983 7.514136 +-0.066267 4.593983 7.323943 +-0.066267 4.727404 7.323943 +0.000000 4.727404 7.271097 +0.000000 4.593983 7.271097 +0.000000 4.727404 7.376789 +0.000000 4.593983 7.376789 +0.385505 4.370259 6.523432 +0.866222 4.370259 7.126232 +0.866222 4.370259 7.521652 +0.385505 4.370259 8.124452 +0.364798 4.531409 6.566432 +0.819694 4.531409 7.136852 +0.819694 4.531409 7.511032 +0.364798 4.531409 8.081452 +0.297577 4.531409 6.706018 +0.668649 4.531409 7.171327 +0.668649 4.531409 7.476558 +0.297577 4.531409 7.941867 +0.220989 4.155853 6.865055 +0.496557 4.155853 7.210606 +0.496557 4.155853 7.437279 +0.220989 4.155853 7.782830 +0.210654 4.593983 6.886514 +0.473336 4.593983 7.215908 +0.473336 4.593983 7.431977 +0.210654 4.593983 7.761370 +0.194826 4.680048 6.919381 +0.437771 4.680048 7.224024 +0.437771 4.680048 7.423861 +0.194827 4.680048 7.728504 +0.158926 4.680048 6.993929 +0.357103 4.680048 7.242437 +0.357103 4.680048 7.405450 +0.158926 4.680048 7.653957 +0.158926 4.593983 6.993929 +0.357103 4.593983 7.242437 +0.357103 4.593983 7.405450 +0.158926 4.593983 7.653957 +0.687283 4.370259 6.775852 +0.687283 4.370259 7.872033 +0.624210 4.531409 6.773306 +0.675731 4.531409 6.837911 +0.675731 4.531409 7.809974 +0.624210 4.531409 7.874579 +0.503082 4.531409 6.869902 +0.554603 4.531409 6.934508 +0.554603 4.531409 7.713378 +0.503082 4.531409 7.777982 +0.392732 4.155853 7.010749 +0.392733 4.155853 7.637136 +0.397973 4.593983 7.059415 +0.346452 4.593983 6.994809 +0.317932 4.680048 7.017554 +0.369453 4.680048 7.082160 +0.346453 4.593983 7.653075 +0.397973 4.593983 7.588469 +0.369453 4.680048 7.565724 +0.317932 4.680048 7.630331 +0.304762 4.680048 7.133748 +0.253241 4.680048 7.069144 +0.304762 4.593983 7.133748 +0.253241 4.593983 7.069144 +0.253241 4.680048 7.578742 +0.304762 4.680048 7.514136 +0.253241 4.593983 7.578742 +0.304762 4.593983 7.514136 +0.066267 4.593983 7.323943 +0.066267 4.727404 7.323943 +-0.280094 4.132950 6.742320 +-0.499355 4.132950 6.925719 +-0.629366 4.132950 7.180293 +-0.629366 4.132950 7.467591 +-0.499356 4.132950 7.722166 +-0.280094 4.132950 7.905565 +0.000000 4.132950 7.969494 +0.000000 4.132950 6.678390 +0.629366 4.132950 7.180293 +0.629366 4.132950 7.467591 +0.280095 4.132950 7.905565 +0.280094 4.132950 6.742320 +0.499356 4.132950 6.925719 +0.499356 4.132950 7.722166 +0.629366 2.835487 7.180293 +0.629366 2.835487 7.467591 +0.499356 2.835487 7.722166 +0.280095 2.835487 7.905565 +0.000000 2.835487 7.969494 +-0.280094 2.835487 7.905565 +-0.499356 2.835487 7.722166 +-0.629366 2.835487 7.467591 +-0.629366 2.835487 7.180293 +-0.176525 4.325351 6.957384 +-0.313714 4.325351 7.073764 +-0.396649 4.325351 7.233410 +-0.396649 4.325351 7.414476 +-0.313714 4.325351 7.574121 +-0.176525 4.325351 7.690501 +0.000000 4.325351 7.730793 +0.000000 4.325351 6.917093 +0.396649 4.325351 7.233410 +0.396649 4.325351 7.414476 +0.176525 4.325351 7.690501 +0.176525 4.325351 6.957384 +0.313714 4.325351 7.073764 +0.313714 4.325351 7.574121 +0.000000 4.478793 7.323944 +-0.985735 2.587556 7.541801 +-0.985735 4.132950 7.541801 +-0.867360 4.132950 7.541801 +-0.867360 2.587556 7.541801 +-0.985735 2.587556 7.176327 +-0.958208 2.587556 7.109871 +-0.891752 2.587556 7.082344 +-0.985735 4.132950 7.176327 +-0.958208 4.132950 7.109871 +-0.891752 4.132950 7.082344 +-0.867360 4.132950 7.274275 +-0.839833 4.132950 7.207819 +-0.773377 4.132950 7.180293 +-0.867360 2.587556 7.274275 +-0.839833 2.587556 7.207819 +-0.773377 2.587556 7.180293 +0.985736 2.587556 7.541801 +0.985736 4.132950 7.541801 +0.867361 4.132950 7.541801 +0.867361 2.587556 7.541801 +0.985736 2.587556 7.176327 +0.958209 2.587556 7.109871 +0.891753 2.587556 7.082344 +0.985736 4.132950 7.176327 +0.958209 4.132950 7.109871 +0.891753 4.132950 7.082344 +0.867361 4.132950 7.274275 +0.839834 4.132950 7.207819 +0.773378 4.132950 7.180293 +0.867361 2.587556 7.274275 +0.839834 2.587556 7.207819 +0.773378 2.587556 7.180293 +-0.891752 3.915582 7.082344 +0.891753 3.915582 7.082344 +-0.379148 3.915582 6.678390 +-0.756861 3.915582 6.880347 +-0.379148 4.132950 6.678390 +-0.756861 4.132950 6.880347 +0.379149 4.132950 6.678390 +0.756861 4.132950 6.880347 +0.379149 3.915582 6.678390 +0.756861 3.915582 6.880347 +-0.301665 4.465046 1.617471 +-0.301665 4.561473 1.450451 +-0.301665 4.508497 1.136557 +-0.301665 4.059140 1.136557 +-0.301665 4.006162 1.450451 +-0.301665 4.102592 1.617471 +-0.301665 4.283817 1.683432 +-0.408417 4.465046 1.617471 +-0.408417 4.561473 1.450451 +-0.408417 4.508497 1.136557 +-0.408417 4.059140 1.136557 +-0.408417 4.006162 1.450451 +-0.408417 4.102592 1.617471 +-0.408417 4.283817 1.683432 +-0.408417 4.442067 1.588901 +-0.408417 4.526267 1.443060 +-0.408417 4.497021 1.277214 +-0.408417 4.368020 1.168966 +-0.408417 4.199618 1.168966 +-0.408417 4.070611 1.277214 +-0.408417 4.041369 1.443060 +-0.408417 4.125572 1.588901 +-0.408417 4.283817 1.646499 +-0.435108 4.442067 1.588901 +-0.435108 4.526267 1.443060 +-0.435108 4.497021 1.277214 +-0.435108 4.368020 1.168966 +-0.435108 4.199618 1.168966 +-0.435108 4.070611 1.277214 +-0.435108 4.041369 1.443060 +-0.435108 4.125572 1.588901 +-0.435108 4.283817 1.646499 +-0.435108 4.385143 1.523734 +-0.435108 4.439054 1.430352 +-0.435108 4.420333 1.324162 +-0.435108 4.337731 1.254851 +-0.435108 4.229903 1.254851 +-0.435108 4.147301 1.324162 +-0.435108 4.128577 1.430352 +-0.435108 4.182493 1.523734 +-0.435108 4.283817 1.560614 +-0.650631 4.385143 1.523734 +-0.650631 4.439054 1.430352 +-0.650631 4.420333 1.324162 +-0.650631 4.337731 1.254851 +-0.650631 4.229903 1.254851 +-0.650631 4.147301 1.324162 +-0.650631 4.128577 1.430352 +-0.650631 4.182493 1.523734 +-0.650631 4.283817 1.560614 +-0.650631 4.283816 1.405597 +-0.301665 4.465046 0.655643 +-0.301665 4.561473 0.822662 +-0.301665 4.006162 0.822662 +-0.301665 4.102592 0.655643 +-0.301665 4.283817 0.589681 +-0.408417 4.465046 0.655643 +-0.408417 4.561473 0.822662 +-0.408417 4.006162 0.822662 +-0.408417 4.102592 0.655643 +-0.408417 4.283817 0.589681 +-0.408417 4.442067 0.684212 +-0.408417 4.526267 0.830054 +-0.408417 4.497021 0.995899 +-0.408417 4.368020 1.104147 +-0.408417 4.199618 1.104147 +-0.408417 4.070611 0.995899 +-0.408417 4.041369 0.830054 +-0.408417 4.125572 0.684212 +-0.408417 4.283817 0.626615 +-0.435108 4.442067 0.684212 +-0.435108 4.526267 0.830054 +-0.435108 4.497021 0.995899 +-0.435108 4.368020 1.104147 +-0.435108 4.199618 1.104147 +-0.435108 4.070611 0.995899 +-0.435108 4.041369 0.830054 +-0.435108 4.125572 0.684212 +-0.435108 4.283817 0.626615 +-0.650631 4.385143 0.749379 +-0.650631 4.439054 0.842761 +-0.650631 4.420333 0.948952 +-0.650631 4.337731 1.018262 +-0.650631 4.229903 1.018262 +-0.650631 4.147301 0.948952 +-0.650631 4.128577 0.842761 +-0.650631 4.182493 0.749379 +-0.650631 4.283817 0.712500 +-0.650631 4.283816 0.867516 +-0.435108 4.385143 0.749379 +-0.435108 4.439054 0.842761 +-0.435108 4.283817 0.712500 +-0.435108 4.182493 0.749379 +-0.435108 4.128577 0.842761 +-0.435108 4.147301 0.948952 +-0.435108 4.229903 1.018262 +-0.435108 4.337731 1.018262 +-0.435108 4.420333 0.948952 +-0.301665 4.283818 0.822662 +-0.301665 4.283817 1.136557 +-0.301665 4.283818 1.450451 +0.301666 4.465046 1.617471 +0.301666 4.561473 1.450451 +0.301666 4.508497 1.136557 +0.301666 4.059140 1.136557 +0.301666 4.006162 1.450451 +0.301666 4.102592 1.617471 +0.301666 4.283817 1.683432 +0.408418 4.465046 1.617471 +0.408418 4.561473 1.450451 +0.408418 4.508497 1.136557 +0.408418 4.059140 1.136557 +0.408418 4.006162 1.450451 +0.408418 4.102592 1.617471 +0.408418 4.283817 1.683432 +0.408418 4.442067 1.588901 +0.408418 4.526267 1.443060 +0.408418 4.497021 1.277214 +0.408418 4.368020 1.168966 +0.408418 4.199618 1.168966 +0.408418 4.070611 1.277214 +0.408418 4.041369 1.443060 +0.408418 4.125572 1.588901 +0.408418 4.283817 1.646499 +0.435109 4.442067 1.588901 +0.435109 4.526267 1.443060 +0.435109 4.497021 1.277214 +0.435109 4.368020 1.168966 +0.435109 4.199618 1.168966 +0.435109 4.070611 1.277214 +0.435109 4.041369 1.443060 +0.435109 4.125572 1.588901 +0.435109 4.283817 1.646499 +0.435109 4.385143 1.523734 +0.435109 4.439054 1.430352 +0.435109 4.420333 1.324162 +0.435109 4.337731 1.254851 +0.435109 4.229903 1.254851 +0.435109 4.147301 1.324162 +0.435109 4.128577 1.430352 +0.435109 4.182493 1.523734 +0.435109 4.283817 1.560614 +0.650632 4.385143 1.523734 +0.650632 4.439054 1.430352 +0.650632 4.420333 1.324162 +0.650632 4.337731 1.254851 +0.650632 4.229903 1.254851 +0.650632 4.147301 1.324162 +0.650632 4.128577 1.430352 +0.650632 4.182493 1.523734 +0.650632 4.283817 1.560614 +0.650632 4.283816 1.405597 +0.301666 4.465046 0.655643 +0.301666 4.561473 0.822662 +0.301666 4.006162 0.822662 +0.301666 4.102592 0.655643 +0.301666 4.283817 0.589681 +0.408418 4.465046 0.655643 +0.408418 4.561473 0.822662 +0.408418 4.006162 0.822662 +0.408418 4.102592 0.655643 +0.408418 4.283817 0.589681 +0.408418 4.442067 0.684212 +0.408418 4.526267 0.830054 +0.408418 4.497021 0.995899 +0.408418 4.368020 1.104147 +0.408418 4.199618 1.104147 +0.408418 4.070611 0.995899 +0.408418 4.041369 0.830054 +0.408418 4.125572 0.684212 +0.408418 4.283817 0.626615 +0.435109 4.442067 0.684212 +0.435109 4.526267 0.830054 +0.435109 4.497021 0.995899 +0.435109 4.368020 1.104147 +0.435109 4.199618 1.104147 +0.435109 4.070611 0.995899 +0.435109 4.041369 0.830054 +0.435109 4.125572 0.684212 +0.435109 4.283817 0.626615 +0.650632 4.385143 0.749379 +0.650632 4.439054 0.842761 +0.650632 4.420333 0.948952 +0.650632 4.337731 1.018262 +0.650632 4.229903 1.018262 +0.650632 4.147301 0.948952 +0.650632 4.128577 0.842761 +0.650632 4.182493 0.749379 +0.650632 4.283817 0.712500 +0.650632 4.283816 0.867516 +0.435109 4.385143 0.749379 +0.435109 4.439054 0.842761 +0.435109 4.283817 0.712500 +0.435109 4.182493 0.749379 +0.435109 4.128577 0.842761 +0.435109 4.147301 0.948952 +0.435109 4.229903 1.018262 +0.435109 4.337731 1.018262 +0.435109 4.420333 0.948952 +0.301666 4.283818 0.822662 +0.301666 4.283817 1.136557 +0.301666 4.283818 1.450451 +-0.301665 4.385143 0.749379 +-0.301665 4.439054 0.842761 +-0.301665 4.420333 0.948952 +-0.301665 4.337731 1.018262 +-0.301665 4.229903 1.018262 +-0.301665 4.147301 0.948952 +-0.301665 4.128577 0.842761 +-0.301665 4.182493 0.749379 +-0.301665 4.283817 0.712500 +0.301666 4.385143 0.749379 +0.301666 4.439054 0.842761 +0.301666 4.420333 0.948952 +0.301666 4.337731 1.018262 +0.301666 4.229903 1.018262 +0.301666 4.147301 0.948952 +0.301666 4.128577 0.842761 +0.301666 4.182493 0.749379 +0.301666 4.283817 0.712500 +-0.152554 4.283816 0.266768 +-0.152554 4.543373 0.346345 +-0.152554 4.617683 0.538459 +-0.152554 4.532749 0.998618 +-0.152554 4.420844 1.094312 +-0.152554 4.283816 0.417777 +-0.152554 4.413702 0.454819 +-0.152554 4.356761 1.029322 +-0.152554 4.417960 0.956946 +-0.152554 4.450886 0.544247 +0.152555 4.283816 0.266768 +0.152555 4.543373 0.346345 +0.152555 4.617683 0.538459 +0.152555 4.532749 0.998618 +0.152555 4.420844 1.094312 +0.152555 4.283816 0.417777 +0.152555 4.413702 0.454819 +0.152555 4.356761 1.029322 +0.152555 4.417960 0.956946 +0.152555 4.450886 0.544247 +-0.152554 4.549975 0.850542 +-0.152554 4.444822 0.849543 +0.152555 4.444822 0.849543 +0.152555 4.549975 0.850542 +-0.152554 4.283816 1.125481 +-0.152554 4.283816 1.048817 +0.152555 4.283816 1.048817 +0.152555 4.283816 1.125481 +-0.152554 4.024258 0.346345 +-0.152554 3.949949 0.538459 +-0.152554 4.034882 0.998618 +-0.152554 4.146787 1.094312 +-0.152554 4.153929 0.454819 +-0.152554 4.210870 1.029322 +-0.152554 4.149671 0.956946 +-0.152554 4.116745 0.544247 +0.152555 4.024258 0.346345 +0.152555 3.949949 0.538459 +0.152555 4.034882 0.998618 +0.152555 4.146787 1.094312 +0.152555 4.153929 0.454819 +0.152555 4.210870 1.029322 +0.152555 4.149671 0.956946 +0.152555 4.116745 0.544247 +-0.152554 4.017656 0.850542 +-0.152554 4.122809 0.849543 +0.152555 4.122809 0.849543 +0.152555 4.017656 0.850542 +0.301666 4.539640 2.104422 +-0.301665 4.539640 2.104422 +0.301666 4.086818 1.196956 +0.301666 4.219674 1.154203 +0.301666 4.031787 1.300173 +-0.301665 4.086818 1.196956 +-0.301665 4.031787 1.300173 +-0.301665 4.219674 1.154203 +0.301666 4.484609 1.196956 +0.301666 4.539640 1.300173 +0.301666 4.351754 1.154203 +-0.301665 4.484609 1.196956 +-0.301665 4.351754 1.154203 +-0.301665 4.539640 1.300173 +-0.301665 4.031787 1.808435 +0.301666 4.031787 1.808435 +0.301666 3.238003 1.808435 +-0.301665 3.238003 1.808435 +0.301666 3.238003 2.104422 +-0.301665 3.238003 2.104422 +-0.065599 4.389340 2.104421 +-0.113621 4.341318 2.104421 +-0.131199 4.275718 2.104421 +-0.113621 4.210119 2.104421 +-0.065599 4.162092 2.104421 +0.000000 4.144519 2.104421 +0.065600 4.162092 2.104421 +0.113622 4.210119 2.104421 +0.131199 4.275718 2.104421 +0.113622 4.341318 2.104421 +0.065600 4.389340 2.104421 +0.000000 4.406917 2.104421 +-0.058951 4.220607 2.650419 +-0.102698 4.182959 2.627218 +-0.118493 4.131069 2.596770 +-0.102104 4.078840 2.567233 +-0.057923 4.040266 2.546520 +0.002212 4.025679 2.540182 +0.062188 4.038993 2.549917 +0.105934 4.076638 2.573115 +0.121729 4.128527 2.603563 +0.105340 4.180757 2.633101 +0.061159 4.219335 2.653815 +0.001024 4.233919 2.660152 +-0.000245 4.098566 2.654361 +-0.073289 4.242104 2.662315 +-0.127392 4.195545 2.633623 +-0.116196 4.157656 2.684430 +-0.067569 4.199503 2.710218 +-0.146926 4.131371 2.595967 +-0.133752 4.099978 2.650586 +-0.126658 4.066777 2.559436 +-0.115536 4.041923 2.617753 +-0.072019 4.019071 2.533821 +-0.066427 3.999044 2.594731 +0.002352 4.001029 2.525981 +0.000415 3.982833 2.587685 +0.076526 4.017497 2.538021 +0.067080 3.997631 2.598506 +0.130628 4.064052 2.566712 +0.115706 4.039475 2.624292 +0.150162 4.128226 2.604366 +0.133263 4.097152 2.658136 +0.129894 4.192821 2.640897 +0.115046 4.155208 2.690969 +0.075253 4.240530 2.666515 +0.065937 4.198090 2.713993 +0.000885 4.258568 2.674353 +-0.000906 4.214300 2.721038 +-0.065599 4.389340 2.192101 +-0.065461 4.375018 2.268523 +-0.113621 4.341318 2.191285 +-0.113448 4.326640 2.268264 +-0.131199 4.275718 2.190727 +-0.130972 4.260572 2.268001 +-0.113621 4.210119 2.190916 +-0.113335 4.194521 2.267877 +-0.065599 4.162092 2.191654 +-0.065267 4.146196 2.267889 +0.000000 4.144519 2.192072 +0.000347 4.128532 2.267919 +0.065600 4.162092 2.191724 +0.065920 4.146231 2.267913 +0.113622 4.210119 2.190981 +0.113890 4.194561 2.267903 +0.131199 4.275718 2.190736 +0.131408 4.260595 2.268011 +0.113622 4.341318 2.191260 +0.113783 4.326648 2.268263 +0.065600 4.389340 2.192079 +0.065731 4.375019 2.268519 +0.000000 4.406917 2.192457 +0.000124 4.392726 2.268624 +0.000000 4.329904 0.120313 +0.000000 4.347226 0.056118 +0.000000 4.328886 -0.010461 +0.000000 4.283816 -0.037967 +0.000000 4.238746 -0.010461 +0.000000 4.220405 0.056118 +0.000000 4.237727 0.120313 +0.000000 4.283816 0.146969 +-0.198759 4.283816 0.175631 +-0.302996 4.283816 0.249611 +-0.206173 4.325064 0.153629 +-0.324568 4.326542 0.244639 +-0.228835 4.342844 0.094346 +-0.386240 4.346151 0.221090 +-0.247672 4.324044 0.036541 +-0.429125 4.323639 0.204304 +-0.254321 4.283816 0.010429 +-0.445920 4.283816 0.193129 +-0.247672 4.243588 0.036541 +-0.429125 4.243992 0.204304 +-0.228835 4.224786 0.094346 +-0.386240 4.221480 0.221090 +-0.206173 4.242568 0.153629 +-0.324568 4.241088 0.244639 +-0.404179 4.283816 0.608871 +-0.427551 4.327574 0.610291 +-0.483975 4.345698 0.613718 +-0.540399 4.327574 0.617144 +-0.563771 4.283816 0.618564 +-0.540399 4.240057 0.617144 +-0.483975 4.221933 0.613718 +-0.427551 4.240057 0.610291 +-0.448453 4.439326 0.723802 +-0.561301 4.439326 0.730656 +-0.561301 4.128306 0.730656 +-0.448453 4.128306 0.723802 +-0.436768 4.283816 1.018986 +-0.572986 4.283816 1.028678 +-0.445026 4.418619 0.985494 +-0.436768 4.362805 1.019695 +-0.448453 4.441777 0.902068 +-0.572986 4.362805 1.027968 +-0.564719 4.418675 0.992849 +-0.561301 4.441777 0.908922 +-0.564719 4.148956 0.992849 +-0.572986 4.204827 1.027968 +-0.561301 4.125854 0.908922 +-0.436768 4.204827 1.019695 +-0.445026 4.149012 0.985494 +-0.448453 4.125854 0.902068 +0.198760 4.283816 0.175631 +0.302996 4.283816 0.249611 +0.206173 4.325064 0.153629 +0.324569 4.326542 0.244639 +0.228835 4.342844 0.094346 +0.386241 4.346151 0.221090 +0.247672 4.324044 0.036541 +0.429126 4.323639 0.204304 +0.254322 4.283816 0.010429 +0.445921 4.283816 0.193129 +0.247672 4.243588 0.036541 +0.429126 4.243992 0.204304 +0.228835 4.224786 0.094346 +0.386241 4.221480 0.221090 +0.206173 4.242568 0.153629 +0.324569 4.241088 0.244639 +0.404179 4.283816 0.608871 +0.427551 4.327574 0.610291 +0.483975 4.345698 0.613718 +0.540400 4.327574 0.617144 +0.563771 4.283816 0.618564 +0.540400 4.240057 0.617144 +0.483975 4.221933 0.613718 +0.427551 4.240057 0.610291 +0.448453 4.439326 0.723802 +0.561302 4.439326 0.730656 +0.561302 4.128306 0.730656 +0.448453 4.128306 0.723802 +0.436769 4.283816 1.018986 +0.572987 4.283816 1.028678 +0.445027 4.418619 0.985494 +0.436769 4.362805 1.019695 +0.448453 4.441777 0.902068 +0.572987 4.362805 1.027968 +0.564720 4.418675 0.992849 +0.561302 4.441777 0.908922 +0.564720 4.148956 0.992849 +0.572987 4.204827 1.027968 +0.561302 4.125854 0.908922 +0.436769 4.204827 1.019695 +0.445027 4.149012 0.985494 +0.448453 4.125854 0.902068 +-0.132215 4.703456 2.271743 +-0.219522 4.536813 2.248226 +-0.217743 4.340063 2.220459 +-0.132215 4.171623 2.196688 +0.000000 4.108848 2.187829 +0.132216 4.171623 2.196688 +0.217743 4.340063 2.220459 +0.219522 4.536813 2.248226 +0.132216 4.703456 2.271743 +0.000000 4.766231 2.280602 +-0.137387 4.708274 2.312782 +-0.228109 4.535112 2.288345 +-0.226260 4.330666 2.259492 +-0.137387 4.155636 2.234791 +0.000000 4.090406 2.225586 +0.137388 4.155636 2.234791 +0.226261 4.330666 2.259492 +0.228109 4.535112 2.288345 +0.137388 4.708274 2.312782 +0.000000 4.773504 2.321988 +-0.150927 4.732055 2.341082 +-0.250590 4.541828 2.314236 +-0.248559 4.317232 2.282540 +-0.150927 4.124952 2.255404 +0.000000 4.053294 2.245292 +0.150928 4.124952 2.255404 +0.248560 4.317232 2.282540 +0.250590 4.541828 2.314236 +0.150928 4.732055 2.341082 +0.000000 4.803714 2.351195 +-0.167664 4.765716 2.345832 +-0.278378 4.554394 2.316009 +-0.276122 4.304892 2.280798 +-0.167664 4.091291 2.250654 +0.000000 4.011686 2.239420 +0.167665 4.091291 2.250654 +0.276123 4.304892 2.280798 +0.278379 4.554394 2.316009 +0.167665 4.765716 2.345832 +0.000000 4.845321 2.357066 +-0.181204 4.796401 2.325219 +-0.300859 4.568012 2.292988 +-0.298421 4.298361 2.254933 +-0.181204 4.067510 2.222355 +0.000000 3.981476 2.210213 +0.181205 4.067510 2.222355 +0.298422 4.298361 2.254933 +0.300860 4.568012 2.292988 +0.181205 4.796401 2.325219 +0.000000 4.882434 2.337361 +-0.186376 4.812387 2.287116 +-0.309446 4.577480 2.253965 +-0.306939 4.300132 2.214824 +-0.186376 4.062692 2.181315 +0.000000 3.974204 2.168827 +0.186377 4.062692 2.181315 +0.306939 4.300132 2.214824 +0.309447 4.577480 2.253965 +0.186377 4.812387 2.287116 +0.000000 4.900876 2.299604 +-0.181204 4.807569 2.246077 +-0.300859 4.579181 2.213845 +-0.298421 4.309530 2.175791 +-0.181204 4.078679 2.143212 +0.000000 3.992645 2.131071 +0.181205 4.078679 2.143212 +0.298422 4.309530 2.175791 +0.300860 4.579180 2.213845 +0.181205 4.807569 2.246077 +0.000000 4.893603 2.258218 +-0.167664 4.783788 2.217777 +-0.278378 4.572465 2.187954 +-0.276122 4.322963 2.152743 +-0.167664 4.109363 2.122599 +0.000000 4.029758 2.111365 +0.167665 4.109363 2.122599 +0.276122 4.322963 2.152743 +0.278379 4.572465 2.187954 +0.167665 4.783788 2.217777 +0.000000 4.863393 2.229012 +-0.150927 4.750127 2.213027 +-0.250590 4.559900 2.186181 +-0.248559 4.335304 2.154485 +-0.150927 4.143024 2.127349 +0.000000 4.071365 2.117237 +0.150928 4.143024 2.127349 +0.248559 4.335304 2.154485 +0.250590 4.559900 2.186181 +0.150928 4.750127 2.213027 +0.000000 4.821785 2.223140 +-0.137387 4.719443 2.233640 +-0.228109 4.546280 2.209203 +-0.226260 4.341834 2.180350 +-0.137387 4.166805 2.155649 +0.000000 4.101575 2.146443 +0.137388 4.166805 2.155649 +0.226261 4.341834 2.180350 +0.228109 4.546280 2.209203 +0.137388 4.719443 2.233640 +0.000000 4.784673 2.242846 +-3.231848 3.719430 5.370928 +-3.220946 3.915583 5.389656 +-2.551843 3.719430 6.539029 +-2.553138 3.915582 6.536804 +3.247100 3.719430 5.344730 +3.239988 3.915582 5.356947 +2.541210 3.719430 6.557295 +2.544988 3.915582 6.550805 +2.543795 -3.719422 6.552854 +2.544498 -3.915574 6.551647 +3.276331 -3.719422 5.294517 +3.277169 -3.915574 5.293079 +-3.257393 -3.719422 5.327049 +-3.253339 -3.915573 5.334014 +-2.527661 -3.719422 6.580569 +-2.528421 -3.915574 6.579263 +</float_array> + <technique_common> + <accessor source="#MineCartEngine-POSITION-array" count="2226" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="MineCartEngine-Normal0"> + <float_array id="MineCartEngine-Normal0-array" count="36810"> +-0.998273 -0.008240 -0.058156 +-0.767116 0.641508 0.000279 +-0.949068 -0.011201 -0.314873 +-0.767116 0.641508 0.000279 +-0.998273 -0.008240 -0.058156 +-0.864466 0.471762 0.173604 +-0.998273 -0.008240 -0.058156 +-0.757415 -0.652710 0.017091 +-0.857331 -0.479999 0.185968 +-0.757415 -0.652710 0.017091 +-0.998273 -0.008240 -0.058156 +-0.949068 -0.011201 -0.314873 +-0.383807 -0.641506 0.664200 +-0.582583 -0.471756 0.661849 +-0.757415 -0.652710 0.017091 +-0.757415 -0.652710 0.017091 +-0.582583 -0.471756 0.661849 +-0.857331 -0.479999 0.185968 +-0.201857 0.011198 0.979351 +-0.582583 -0.471756 0.661849 +-0.383807 -0.641506 0.664200 +-0.582583 -0.471756 0.661849 +-0.201857 0.011198 0.979351 +-0.448779 0.008237 0.893605 +-0.201857 0.011198 0.979351 +-0.589717 0.480001 0.649487 +-0.448779 0.008237 0.893605 +-0.589717 0.480001 0.649487 +-0.201857 0.011198 0.979351 +-0.393507 0.652714 0.647392 +-0.864466 0.471762 0.173604 +-0.393507 0.652714 0.647392 +-0.767116 0.641508 0.000279 +-0.393507 0.652714 0.647392 +-0.864466 0.471762 0.173604 +-0.589717 0.480001 0.649487 +-0.582583 -0.471756 0.661849 +-0.998273 -0.008240 -0.058156 +-0.857331 -0.479999 0.185968 +-0.998273 -0.008240 -0.058156 +-0.582583 -0.471756 0.661849 +-0.448779 0.008237 0.893605 +-0.448779 0.008237 0.893605 +-0.864466 0.471762 0.173604 +-0.998273 -0.008240 -0.058156 +-0.448779 0.008237 0.893605 +-0.589717 0.480001 0.649487 +-0.864466 0.471762 0.173604 +-0.899055 0.373648 -0.228228 +-0.899051 -0.373648 -0.228240 +-0.961492 -0.274778 0.005559 +-0.899055 0.373648 -0.228228 +-0.961492 -0.274778 0.005559 +-0.961491 0.274779 0.005570 +-0.575459 -0.747303 0.332245 +-0.961492 -0.274778 0.005559 +-0.899051 -0.373648 -0.228240 +-0.961492 -0.274778 0.005559 +-0.575459 -0.747303 0.332245 +-0.723527 -0.549558 0.417725 +-0.251859 -0.373646 0.892724 +-0.485558 -0.274776 0.829899 +-0.575459 -0.747303 0.332245 +-0.575459 -0.747303 0.332245 +-0.485558 -0.274776 0.829899 +-0.723527 -0.549558 0.417725 +-0.485562 0.274784 0.829894 +-0.251859 -0.373646 0.892724 +-0.251871 0.373657 0.892716 +-0.251859 -0.373646 0.892724 +-0.485562 0.274784 0.829894 +-0.485558 -0.274776 0.829899 +-0.575465 0.747303 0.332232 +-0.485562 0.274784 0.829894 +-0.251871 0.373657 0.892716 +-0.485562 0.274784 0.829894 +-0.575465 0.747303 0.332232 +-0.723527 0.549557 0.417726 +-0.961491 0.274779 0.005570 +-0.575465 0.747303 0.332232 +-0.899055 0.373648 -0.228228 +-0.575465 0.747303 0.332232 +-0.961491 0.274779 0.005570 +-0.723527 0.549557 0.417726 +-0.961492 -0.274778 0.005559 +-0.485558 -0.274776 0.829899 +-0.485562 0.274784 0.829894 +-0.485558 -0.274776 0.829899 +-0.961492 -0.274778 0.005559 +-0.723527 -0.549558 0.417725 +-0.961492 -0.274778 0.005559 +-0.485562 0.274784 0.829894 +-0.961491 0.274779 0.005570 +-0.961491 0.274779 0.005570 +-0.485562 0.274784 0.829894 +-0.723527 0.549557 0.417726 +-0.860799 0.482482 -0.161976 +-0.927049 -0.252988 -0.276727 +-0.982081 -0.186040 -0.030107 +-0.860799 0.482482 -0.161976 +-0.982081 -0.186040 -0.030107 +-0.933361 0.354810 0.054280 +-0.641722 -0.735451 0.217496 +-0.982081 -0.186040 -0.030107 +-0.927049 -0.252988 -0.276727 +-0.982081 -0.186040 -0.030107 +-0.641722 -0.735451 0.217496 +-0.772250 -0.540843 0.333345 +-0.290130 -0.482470 0.826467 +-0.513693 -0.354802 0.781175 +-0.641722 -0.735451 0.217496 +-0.641722 -0.735451 0.217496 +-0.513693 -0.354802 0.781175 +-0.772250 -0.540843 0.333345 +-0.223879 0.252985 0.941210 +-0.513693 -0.354802 0.781175 +-0.290130 -0.482470 0.826467 +-0.513693 -0.354802 0.781175 +-0.223879 0.252985 0.941210 +-0.464975 0.186042 0.865556 +-0.509210 0.735465 0.446986 +-0.464975 0.186042 0.865556 +-0.223879 0.252985 0.941210 +-0.464975 0.186042 0.865556 +-0.509210 0.735465 0.446986 +-0.674806 0.540855 0.502108 +-0.860799 0.482482 -0.161976 +-0.933361 0.354810 0.054280 +-0.509210 0.735465 0.446986 +-0.509210 0.735465 0.446986 +-0.933361 0.354810 0.054280 +-0.674806 0.540855 0.502108 +-0.982081 -0.186040 -0.030107 +-0.513693 -0.354802 0.781175 +-0.464975 0.186042 0.865556 +-0.513693 -0.354802 0.781175 +-0.982081 -0.186040 -0.030107 +-0.772250 -0.540843 0.333345 +-0.933361 0.354810 0.054280 +-0.982081 -0.186040 -0.030107 +-0.464975 0.186042 0.865556 +-0.933361 0.354810 0.054280 +-0.464975 0.186042 0.865556 +-0.674806 0.540855 0.502108 +-0.857072 0.491160 -0.155529 +-0.928944 -0.242191 -0.280013 +-0.983474 -0.178107 -0.032516 +-0.857072 0.491160 -0.155529 +-0.983474 -0.178107 -0.032516 +-0.930623 0.361188 0.059027 +-0.647328 -0.733354 0.207746 +-0.983474 -0.178107 -0.032516 +-0.928944 -0.242191 -0.280013 +-0.983474 -0.178107 -0.032516 +-0.647328 -0.733354 0.207746 +-0.776378 -0.539303 0.326174 +-0.293843 -0.491161 0.820010 +-0.516427 -0.361198 0.776427 +-0.647328 -0.733354 0.207746 +-0.647328 -0.733354 0.207746 +-0.516427 -0.361198 0.776427 +-0.776378 -0.539303 0.326174 +-0.221972 0.242186 0.944497 +-0.516427 -0.361198 0.776427 +-0.293843 -0.491161 0.820010 +-0.516427 -0.361198 0.776427 +-0.221972 0.242186 0.944497 +-0.463572 0.178097 0.867976 +-0.503592 0.733343 0.456730 +-0.463572 0.178097 0.867976 +-0.221972 0.242186 0.944497 +-0.463572 0.178097 0.867976 +-0.503592 0.733343 0.456730 +-0.670675 0.539292 0.509273 +-0.857072 0.491160 -0.155529 +-0.930623 0.361188 0.059027 +-0.503592 0.733343 0.456730 +-0.503592 0.733343 0.456730 +-0.930623 0.361188 0.059027 +-0.670675 0.539292 0.509273 +-0.983474 -0.178107 -0.032516 +-0.516427 -0.361198 0.776427 +-0.463572 0.178097 0.867976 +-0.516427 -0.361198 0.776427 +-0.983474 -0.178107 -0.032516 +-0.776378 -0.539303 0.326174 +-0.930623 0.361188 0.059027 +-0.983474 -0.178107 -0.032516 +-0.463572 0.178097 0.867976 +-0.930623 0.361188 0.059027 +-0.463572 0.178097 0.867976 +-0.670675 0.539292 0.509273 +-0.998274 0.008236 -0.058151 +-0.949069 0.011205 -0.314870 +-0.767112 -0.641513 0.000271 +-0.998274 0.008236 -0.058151 +-0.767112 -0.641513 0.000271 +-0.864464 -0.471766 0.173607 +-0.998274 0.008236 -0.058151 +-0.757420 0.652705 0.017097 +-0.949069 0.011205 -0.314870 +-0.757420 0.652705 0.017097 +-0.998274 0.008236 -0.058151 +-0.857334 0.479993 0.185969 +-0.383813 0.641504 0.664199 +-0.757420 0.652705 0.017097 +-0.582584 0.471759 0.661845 +-0.757420 0.652705 0.017097 +-0.857334 0.479993 0.185969 +-0.582584 0.471759 0.661845 +-0.582584 0.471759 0.661845 +-0.201847 -0.011194 0.979353 +-0.383813 0.641504 0.664199 +-0.201847 -0.011194 0.979353 +-0.582584 0.471759 0.661845 +-0.448775 -0.008239 0.893607 +-0.589712 -0.480005 0.649488 +-0.201847 -0.011194 0.979353 +-0.448775 -0.008239 0.893607 +-0.393493 -0.652718 0.647396 +-0.201847 -0.011194 0.979353 +-0.589712 -0.480005 0.649488 +-0.767112 -0.641513 0.000271 +-0.393493 -0.652718 0.647396 +-0.864464 -0.471766 0.173607 +-0.393493 -0.652718 0.647396 +-0.589712 -0.480005 0.649488 +-0.864464 -0.471766 0.173607 +-0.582584 0.471759 0.661845 +-0.998274 0.008236 -0.058151 +-0.448775 -0.008239 0.893607 +-0.998274 0.008236 -0.058151 +-0.582584 0.471759 0.661845 +-0.857334 0.479993 0.185969 +-0.448775 -0.008239 0.893607 +-0.864464 -0.471766 0.173607 +-0.589712 -0.480005 0.649488 +-0.448775 -0.008239 0.893607 +-0.998274 0.008236 -0.058151 +-0.864464 -0.471766 0.173607 +-0.899054 -0.373642 -0.228241 +-0.961490 0.274783 0.005562 +-0.899054 0.373645 -0.228235 +-0.961490 0.274783 0.005562 +-0.899054 -0.373642 -0.228241 +-0.961492 -0.274777 0.005563 +-0.961490 0.274783 0.005562 +-0.575455 0.747307 0.332240 +-0.899054 0.373645 -0.228235 +-0.575455 0.747307 0.332240 +-0.961490 0.274783 0.005562 +-0.723527 0.549557 0.417726 +-0.251869 0.373649 0.892720 +-0.575455 0.747307 0.332240 +-0.485561 0.274786 0.829893 +-0.575455 0.747307 0.332240 +-0.723527 0.549557 0.417726 +-0.485561 0.274786 0.829893 +-0.485558 -0.274779 0.829897 +-0.251869 0.373649 0.892720 +-0.485561 0.274786 0.829893 +-0.251869 0.373649 0.892720 +-0.485558 -0.274779 0.829897 +-0.251864 -0.373646 0.892722 +-0.485558 -0.274779 0.829897 +-0.575460 -0.747302 0.332243 +-0.251864 -0.373646 0.892722 +-0.575460 -0.747302 0.332243 +-0.485558 -0.274779 0.829897 +-0.723525 -0.549557 0.417731 +-0.899054 -0.373642 -0.228241 +-0.575460 -0.747302 0.332243 +-0.961492 -0.274777 0.005563 +-0.575460 -0.747302 0.332243 +-0.723525 -0.549557 0.417731 +-0.961492 -0.274777 0.005563 +-0.485561 0.274786 0.829893 +-0.961490 0.274783 0.005562 +-0.485558 -0.274779 0.829897 +-0.961490 0.274783 0.005562 +-0.485561 0.274786 0.829893 +-0.723527 0.549557 0.417726 +-0.961492 -0.274777 0.005563 +-0.723525 -0.549557 0.417731 +-0.485558 -0.274779 0.829897 +-0.961492 -0.274777 0.005563 +-0.485558 -0.274779 0.829897 +-0.961490 0.274783 0.005562 +-0.860802 -0.482477 -0.161977 +-0.982081 0.186040 -0.030106 +-0.927050 0.252988 -0.276724 +-0.982081 0.186040 -0.030106 +-0.860802 -0.482477 -0.161977 +-0.933360 -0.354813 0.054276 +-0.982081 0.186040 -0.030106 +-0.641718 0.735453 0.217500 +-0.927050 0.252988 -0.276724 +-0.641718 0.735453 0.217500 +-0.982081 0.186040 -0.030106 +-0.772248 0.540844 0.333346 +-0.290129 0.482471 0.826467 +-0.641718 0.735453 0.217500 +-0.513694 0.354803 0.781174 +-0.641718 0.735453 0.217500 +-0.772248 0.540844 0.333346 +-0.513694 0.354803 0.781174 +-0.513694 0.354803 0.781174 +-0.223873 -0.252980 0.941213 +-0.290129 0.482471 0.826467 +-0.223873 -0.252980 0.941213 +-0.513694 0.354803 0.781174 +-0.464970 -0.186047 0.865557 +-0.509207 -0.735464 0.446990 +-0.464970 -0.186047 0.865557 +-0.674805 -0.540849 0.502116 +-0.464970 -0.186047 0.865557 +-0.509207 -0.735464 0.446990 +-0.223873 -0.252980 0.941213 +-0.860802 -0.482477 -0.161977 +-0.509207 -0.735464 0.446990 +-0.933360 -0.354813 0.054276 +-0.509207 -0.735464 0.446990 +-0.674805 -0.540849 0.502116 +-0.933360 -0.354813 0.054276 +-0.513694 0.354803 0.781174 +-0.982081 0.186040 -0.030106 +-0.464970 -0.186047 0.865557 +-0.982081 0.186040 -0.030106 +-0.513694 0.354803 0.781174 +-0.772248 0.540844 0.333346 +-0.464970 -0.186047 0.865557 +-0.933360 -0.354813 0.054276 +-0.674805 -0.540849 0.502116 +-0.933360 -0.354813 0.054276 +-0.464970 -0.186047 0.865557 +-0.982081 0.186040 -0.030106 +-0.857071 -0.491164 -0.155524 +-0.983473 0.178113 -0.032519 +-0.928944 0.242189 -0.280013 +-0.983473 0.178113 -0.032519 +-0.857071 -0.491164 -0.155524 +-0.930622 -0.361191 0.059030 +-0.983473 0.178113 -0.032519 +-0.647330 0.733347 0.207763 +-0.928944 0.242189 -0.280013 +-0.647330 0.733347 0.207763 +-0.983473 0.178113 -0.032519 +-0.776375 0.539302 0.326182 +-0.293855 0.491160 0.820007 +-0.647330 0.733347 0.207763 +-0.516427 0.361197 0.776428 +-0.647330 0.733347 0.207763 +-0.776375 0.539302 0.326182 +-0.516427 0.361197 0.776428 +-0.516427 0.361197 0.776428 +-0.221978 -0.242192 0.944494 +-0.293855 0.491160 0.820007 +-0.221978 -0.242192 0.944494 +-0.516427 0.361197 0.776428 +-0.463578 -0.178101 0.867972 +-0.503581 -0.733351 0.456730 +-0.463578 -0.178101 0.867972 +-0.670673 -0.539294 0.509274 +-0.463578 -0.178101 0.867972 +-0.503581 -0.733351 0.456730 +-0.221978 -0.242192 0.944494 +-0.857071 -0.491164 -0.155524 +-0.503581 -0.733351 0.456730 +-0.930622 -0.361191 0.059030 +-0.503581 -0.733351 0.456730 +-0.670673 -0.539294 0.509274 +-0.930622 -0.361191 0.059030 +-0.516427 0.361197 0.776428 +-0.983473 0.178113 -0.032519 +-0.463578 -0.178101 0.867972 +-0.983473 0.178113 -0.032519 +-0.516427 0.361197 0.776428 +-0.776375 0.539302 0.326182 +-0.463578 -0.178101 0.867972 +-0.930622 -0.361191 0.059030 +-0.670673 -0.539294 0.509274 +-0.930622 -0.361191 0.059030 +-0.463578 -0.178101 0.867972 +-0.983473 0.178113 -0.032519 +0.998274 -0.008239 -0.058155 +0.949069 -0.011201 -0.314870 +0.767117 0.641507 0.000276 +0.998274 -0.008239 -0.058155 +0.767117 0.641507 0.000276 +0.864467 0.471763 0.173600 +0.998274 -0.008239 -0.058155 +0.757417 -0.652708 0.017097 +0.949069 -0.011201 -0.314870 +0.757417 -0.652708 0.017097 +0.998274 -0.008239 -0.058155 +0.857330 -0.479999 0.185973 +0.383806 -0.641504 0.664203 +0.757417 -0.652708 0.017097 +0.582580 -0.471756 0.661851 +0.757417 -0.652708 0.017097 +0.857330 -0.479999 0.185973 +0.582580 -0.471756 0.661851 +0.201857 0.011199 0.979351 +0.582580 -0.471756 0.661851 +0.448779 0.008238 0.893605 +0.582580 -0.471756 0.661851 +0.201857 0.011199 0.979351 +0.383806 -0.641504 0.664203 +0.201857 0.011199 0.979351 +0.589719 0.480004 0.649483 +0.393509 0.652716 0.647389 +0.589719 0.480004 0.649483 +0.201857 0.011199 0.979351 +0.448779 0.008238 0.893605 +0.767117 0.641507 0.000276 +0.393509 0.652716 0.647389 +0.864467 0.471763 0.173600 +0.393509 0.652716 0.647389 +0.589719 0.480004 0.649483 +0.864467 0.471763 0.173600 +0.582580 -0.471756 0.661851 +0.998274 -0.008239 -0.058155 +0.448779 0.008238 0.893605 +0.998274 -0.008239 -0.058155 +0.582580 -0.471756 0.661851 +0.857330 -0.479999 0.185973 +0.448779 0.008238 0.893605 +0.864467 0.471763 0.173600 +0.589719 0.480004 0.649483 +0.448779 0.008238 0.893605 +0.998274 -0.008239 -0.058155 +0.864467 0.471763 0.173600 +0.899055 0.373646 -0.228229 +0.961492 -0.274777 0.005560 +0.899052 -0.373647 -0.228238 +0.961492 -0.274777 0.005560 +0.899055 0.373646 -0.228229 +0.961492 0.274778 0.005571 +0.961492 -0.274777 0.005560 +0.575460 -0.747300 0.332247 +0.899052 -0.373647 -0.228238 +0.575460 -0.747300 0.332247 +0.961492 -0.274777 0.005560 +0.723527 -0.549557 0.417726 +0.251868 -0.373646 0.892721 +0.575460 -0.747300 0.332247 +0.485564 -0.274776 0.829895 +0.575460 -0.747300 0.332247 +0.723527 -0.549557 0.417726 +0.485564 -0.274776 0.829895 +0.485565 0.274782 0.829892 +0.251876 0.373655 0.892715 +0.251868 -0.373646 0.892721 +0.485565 0.274782 0.829892 +0.251868 -0.373646 0.892721 +0.485564 -0.274776 0.829895 +0.485565 0.274782 0.829892 +0.575466 0.747301 0.332236 +0.251876 0.373655 0.892715 +0.575466 0.747301 0.332236 +0.485565 0.274782 0.829892 +0.723527 0.549555 0.417729 +0.899055 0.373646 -0.228229 +0.575466 0.747301 0.332236 +0.961492 0.274778 0.005571 +0.575466 0.747301 0.332236 +0.723527 0.549555 0.417729 +0.961492 0.274778 0.005571 +0.485564 -0.274776 0.829895 +0.961492 -0.274777 0.005560 +0.485565 0.274782 0.829892 +0.961492 -0.274777 0.005560 +0.485564 -0.274776 0.829895 +0.723527 -0.549557 0.417726 +0.961492 0.274778 0.005571 +0.723527 0.549555 0.417729 +0.485565 0.274782 0.829892 +0.961492 0.274778 0.005571 +0.485565 0.274782 0.829892 +0.961492 -0.274777 0.005560 +0.860799 0.482480 -0.161983 +0.982081 -0.186042 -0.030106 +0.927049 -0.252990 -0.276726 +0.982081 -0.186042 -0.030106 +0.860799 0.482480 -0.161983 +0.933362 0.354810 0.054274 +0.982081 -0.186042 -0.030106 +0.641719 -0.735454 0.217496 +0.927049 -0.252990 -0.276726 +0.641719 -0.735454 0.217496 +0.982081 -0.186042 -0.030106 +0.772248 -0.540846 0.333346 +0.290128 -0.482471 0.826467 +0.641719 -0.735454 0.217496 +0.513692 -0.354803 0.781176 +0.641719 -0.735454 0.217496 +0.772248 -0.540846 0.333346 +0.513692 -0.354803 0.781176 +0.223875 0.252987 0.941211 +0.513692 -0.354803 0.781176 +0.464973 0.186043 0.865556 +0.513692 -0.354803 0.781176 +0.223875 0.252987 0.941211 +0.290128 -0.482471 0.826467 +0.509213 0.735467 0.446979 +0.464973 0.186043 0.865556 +0.674809 0.540857 0.502103 +0.464973 0.186043 0.865556 +0.509213 0.735467 0.446979 +0.223875 0.252987 0.941211 +0.860799 0.482480 -0.161983 +0.509213 0.735467 0.446979 +0.933362 0.354810 0.054274 +0.509213 0.735467 0.446979 +0.674809 0.540857 0.502103 +0.933362 0.354810 0.054274 +0.513692 -0.354803 0.781176 +0.982081 -0.186042 -0.030106 +0.464973 0.186043 0.865556 +0.982081 -0.186042 -0.030106 +0.513692 -0.354803 0.781176 +0.772248 -0.540846 0.333346 +0.464973 0.186043 0.865556 +0.933362 0.354810 0.054274 +0.674809 0.540857 0.502103 +0.933362 0.354810 0.054274 +0.464973 0.186043 0.865556 +0.982081 -0.186042 -0.030106 +0.857070 0.491163 -0.155530 +0.983473 -0.178109 -0.032515 +0.928943 -0.242194 -0.280011 +0.983473 -0.178109 -0.032515 +0.857070 0.491163 -0.155530 +0.930623 0.361189 0.059025 +0.983473 -0.178109 -0.032515 +0.647327 -0.733355 0.207747 +0.928943 -0.242194 -0.280011 +0.647327 -0.733355 0.207747 +0.983473 -0.178109 -0.032515 +0.776377 -0.539303 0.326176 +0.293845 -0.491160 0.820010 +0.647327 -0.733355 0.207747 +0.516428 -0.361197 0.776427 +0.647327 -0.733355 0.207747 +0.776377 -0.539303 0.326176 +0.516428 -0.361197 0.776427 +0.221973 0.242185 0.944497 +0.516428 -0.361197 0.776427 +0.463573 0.178095 0.867976 +0.516428 -0.361197 0.776427 +0.221973 0.242185 0.944497 +0.293845 -0.491160 0.820010 +0.503588 0.733346 0.456731 +0.463573 0.178095 0.867976 +0.670674 0.539294 0.509273 +0.463573 0.178095 0.867976 +0.503588 0.733346 0.456731 +0.221973 0.242185 0.944497 +0.857070 0.491163 -0.155530 +0.503588 0.733346 0.456731 +0.930623 0.361189 0.059025 +0.503588 0.733346 0.456731 +0.670674 0.539294 0.509273 +0.930623 0.361189 0.059025 +0.516428 -0.361197 0.776427 +0.983473 -0.178109 -0.032515 +0.463573 0.178095 0.867976 +0.983473 -0.178109 -0.032515 +0.516428 -0.361197 0.776427 +0.776377 -0.539303 0.326176 +0.463573 0.178095 0.867976 +0.930623 0.361189 0.059025 +0.670674 0.539294 0.509273 +0.930623 0.361189 0.059025 +0.463573 0.178095 0.867976 +0.983473 -0.178109 -0.032515 +0.998274 0.008237 -0.058154 +0.767112 -0.641514 0.000269 +0.949068 0.011208 -0.314872 +0.767112 -0.641514 0.000269 +0.998274 0.008237 -0.058154 +0.864464 -0.471766 0.173604 +0.998274 0.008237 -0.058154 +0.757418 0.652706 0.017098 +0.857335 0.479993 0.185969 +0.757418 0.652706 0.017098 +0.998274 0.008237 -0.058154 +0.949068 0.011208 -0.314872 +0.383812 0.641503 0.664200 +0.582585 0.471757 0.661846 +0.757418 0.652706 0.017098 +0.757418 0.652706 0.017098 +0.582585 0.471757 0.661846 +0.857335 0.479993 0.185969 +0.582585 0.471757 0.661846 +0.201849 -0.011195 0.979353 +0.448777 -0.008240 0.893606 +0.201849 -0.011195 0.979353 +0.582585 0.471757 0.661846 +0.383812 0.641503 0.664200 +0.393494 -0.652718 0.647396 +0.589713 -0.480005 0.649487 +0.201849 -0.011195 0.979353 +0.201849 -0.011195 0.979353 +0.589713 -0.480005 0.649487 +0.448777 -0.008240 0.893606 +0.864464 -0.471766 0.173604 +0.393494 -0.652718 0.647396 +0.767112 -0.641514 0.000269 +0.393494 -0.652718 0.647396 +0.864464 -0.471766 0.173604 +0.589713 -0.480005 0.649487 +0.582585 0.471757 0.661846 +0.998274 0.008237 -0.058154 +0.857335 0.479993 0.185969 +0.998274 0.008237 -0.058154 +0.582585 0.471757 0.661846 +0.448777 -0.008240 0.893606 +0.448777 -0.008240 0.893606 +0.864464 -0.471766 0.173604 +0.998274 0.008237 -0.058154 +0.448777 -0.008240 0.893606 +0.589713 -0.480005 0.649487 +0.864464 -0.471766 0.173604 +0.899054 -0.373642 -0.228242 +0.899054 0.373645 -0.228235 +0.961490 0.274783 0.005562 +0.899054 -0.373642 -0.228242 +0.961490 0.274783 0.005562 +0.961492 -0.274776 0.005561 +0.575455 0.747307 0.332240 +0.961490 0.274783 0.005562 +0.899054 0.373645 -0.228235 +0.961490 0.274783 0.005562 +0.575455 0.747307 0.332240 +0.723527 0.549557 0.417727 +0.251869 0.373649 0.892720 +0.485560 0.274786 0.829894 +0.575455 0.747307 0.332240 +0.575455 0.747307 0.332240 +0.485560 0.274786 0.829894 +0.723527 0.549557 0.417727 +0.485560 0.274786 0.829894 +0.251869 0.373649 0.892720 +0.485559 -0.274779 0.829897 +0.251869 0.373649 0.892720 +0.251864 -0.373646 0.892722 +0.485559 -0.274779 0.829897 +0.575461 -0.747302 0.332242 +0.485559 -0.274779 0.829897 +0.251864 -0.373646 0.892722 +0.485559 -0.274779 0.829897 +0.575461 -0.747302 0.332242 +0.723526 -0.549557 0.417729 +0.961492 -0.274776 0.005561 +0.575461 -0.747302 0.332242 +0.899054 -0.373642 -0.228242 +0.575461 -0.747302 0.332242 +0.961492 -0.274776 0.005561 +0.723526 -0.549557 0.417729 +0.961490 0.274783 0.005562 +0.485560 0.274786 0.829894 +0.485559 -0.274779 0.829897 +0.485560 0.274786 0.829894 +0.961490 0.274783 0.005562 +0.723527 0.549557 0.417727 +0.961490 0.274783 0.005562 +0.485559 -0.274779 0.829897 +0.961492 -0.274776 0.005561 +0.961492 -0.274776 0.005561 +0.485559 -0.274779 0.829897 +0.723526 -0.549557 0.417729 +0.860803 -0.482476 -0.161976 +0.927050 0.252985 -0.276724 +0.982081 0.186038 -0.030106 +0.860803 -0.482476 -0.161976 +0.982081 0.186038 -0.030106 +0.933361 -0.354812 0.054279 +0.641721 0.735450 0.217501 +0.982081 0.186038 -0.030106 +0.927050 0.252985 -0.276724 +0.982081 0.186038 -0.030106 +0.641721 0.735450 0.217501 +0.772251 0.540842 0.333345 +0.290129 0.482471 0.826467 +0.513695 0.354803 0.781173 +0.641721 0.735450 0.217501 +0.641721 0.735450 0.217501 +0.513695 0.354803 0.781173 +0.772251 0.540842 0.333345 +0.513695 0.354803 0.781173 +0.223875 -0.252982 0.941212 +0.464971 -0.186048 0.865556 +0.223875 -0.252982 0.941212 +0.513695 0.354803 0.781173 +0.290129 0.482471 0.826467 +0.509208 -0.735464 0.446990 +0.464971 -0.186048 0.865556 +0.223875 -0.252982 0.941212 +0.464971 -0.186048 0.865556 +0.509208 -0.735464 0.446990 +0.674805 -0.540848 0.502117 +0.860803 -0.482476 -0.161976 +0.933361 -0.354812 0.054279 +0.509208 -0.735464 0.446990 +0.509208 -0.735464 0.446990 +0.933361 -0.354812 0.054279 +0.674805 -0.540848 0.502117 +0.982081 0.186038 -0.030106 +0.513695 0.354803 0.781173 +0.464971 -0.186048 0.865556 +0.513695 0.354803 0.781173 +0.982081 0.186038 -0.030106 +0.772251 0.540842 0.333345 +0.933361 -0.354812 0.054279 +0.982081 0.186038 -0.030106 +0.464971 -0.186048 0.865556 +0.933361 -0.354812 0.054279 +0.464971 -0.186048 0.865556 +0.674805 -0.540848 0.502117 +0.857072 -0.491162 -0.155525 +0.928945 0.242186 -0.280014 +0.983473 0.178109 -0.032520 +0.857072 -0.491162 -0.155525 +0.983473 0.178109 -0.032520 +0.930622 -0.361191 0.059030 +0.647332 0.733345 0.207763 +0.983473 0.178109 -0.032520 +0.928945 0.242186 -0.280014 +0.983473 0.178109 -0.032520 +0.647332 0.733345 0.207763 +0.776377 0.539300 0.326182 +0.293854 0.491160 0.820007 +0.516427 0.361197 0.776428 +0.647332 0.733345 0.207763 +0.647332 0.733345 0.207763 +0.516427 0.361197 0.776428 +0.776377 0.539300 0.326182 +0.516427 0.361197 0.776428 +0.221975 -0.242192 0.944495 +0.463576 -0.178101 0.867973 +0.221975 -0.242192 0.944495 +0.516427 0.361197 0.776428 +0.293854 0.491160 0.820007 +0.503582 -0.733350 0.456731 +0.463576 -0.178101 0.867973 +0.221975 -0.242192 0.944495 +0.463576 -0.178101 0.867973 +0.503582 -0.733350 0.456731 +0.670673 -0.539294 0.509274 +0.857072 -0.491162 -0.155525 +0.930622 -0.361191 0.059030 +0.503582 -0.733350 0.456731 +0.503582 -0.733350 0.456731 +0.930622 -0.361191 0.059030 +0.670673 -0.539294 0.509274 +0.983473 0.178109 -0.032520 +0.516427 0.361197 0.776428 +0.463576 -0.178101 0.867973 +0.516427 0.361197 0.776428 +0.983473 0.178109 -0.032520 +0.776377 0.539300 0.326182 +0.930622 -0.361191 0.059030 +0.983473 0.178109 -0.032520 +0.463576 -0.178101 0.867973 +0.930622 -0.361191 0.059030 +0.463576 -0.178101 0.867973 +0.670673 -0.539294 0.509274 +-0.900721 0.000000 0.434398 +-0.900721 0.000000 0.434398 +-0.900721 0.000000 0.434398 +-0.900721 0.000000 0.434398 +-0.900721 0.000000 0.434398 +-0.900721 0.000000 0.434398 +-0.074158 0.000000 0.997247 +-0.074158 0.000000 0.997247 +-0.074158 0.000000 0.997247 +-0.074158 0.000000 0.997247 +-0.074158 0.000000 0.997247 +-0.074158 0.000000 0.997247 +0.826561 -0.000000 0.562847 +0.826561 -0.000000 0.562847 +0.826561 -0.000000 0.562847 +0.826561 -0.000000 0.562847 +0.826561 -0.000000 0.562847 +0.826561 -0.000000 0.562847 +0.900721 -0.000000 -0.434399 +0.900721 -0.000000 -0.434399 +0.900721 -0.000000 -0.434399 +0.900721 -0.000000 -0.434399 +0.900721 -0.000000 -0.434399 +0.900721 -0.000000 -0.434399 +0.074159 -0.000000 -0.997246 +0.074159 -0.000000 -0.997246 +0.074159 -0.000000 -0.997246 +0.074159 -0.000000 -0.997246 +0.074159 -0.000000 -0.997246 +0.074159 -0.000000 -0.997246 +-0.826561 0.000000 -0.562847 +-0.826561 0.000000 -0.562847 +-0.826561 0.000000 -0.562847 +-0.826561 0.000000 -0.562847 +-0.826561 0.000000 -0.562847 +-0.826561 0.000000 -0.562847 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000006 +0.000000 1.000000 -0.000000 +-0.990034 0.000000 0.140831 +-0.990034 0.000000 0.140831 +-0.990034 0.000000 0.140831 +-0.990034 0.000000 0.140831 +-0.990034 0.000000 0.140831 +-0.990034 0.000000 0.140831 +-0.373058 0.000000 0.927808 +-0.373058 0.000000 0.927808 +-0.373058 0.000000 0.927808 +-0.373058 0.000000 0.927808 +-0.373058 0.000000 0.927808 +-0.373058 0.000000 0.927808 +0.616979 -0.000000 0.786980 +0.616979 -0.000000 0.786980 +0.616979 -0.000000 0.786980 +0.616979 -0.000000 0.786980 +0.616979 -0.000000 0.786980 +0.616979 -0.000000 0.786980 +0.990034 -0.000000 -0.140831 +0.990034 -0.000000 -0.140831 +0.990034 -0.000000 -0.140831 +0.990034 -0.000000 -0.140831 +0.990034 -0.000000 -0.140831 +0.990034 -0.000000 -0.140831 +0.373057 -0.000000 -0.927808 +0.373057 -0.000000 -0.927808 +0.373057 -0.000000 -0.927808 +0.373057 -0.000000 -0.927808 +0.373057 -0.000000 -0.927808 +0.373057 -0.000000 -0.927808 +-0.616979 0.000000 -0.786980 +-0.616979 0.000000 -0.786980 +-0.616979 0.000000 -0.786980 +-0.616979 0.000000 -0.786980 +-0.616979 0.000000 -0.786980 +-0.616979 0.000000 -0.786980 +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.000003 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000003 +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.000003 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000003 +0.000000 1.000000 0.000003 +0.000000 1.000000 0.000000 +0.900721 -0.000000 0.434398 +0.900721 -0.000000 0.434398 +0.900721 -0.000000 0.434398 +0.900721 -0.000000 0.434398 +0.900721 -0.000000 0.434398 +0.900721 -0.000000 0.434398 +0.074158 -0.000000 0.997247 +0.074158 -0.000000 0.997247 +0.074158 -0.000000 0.997247 +0.074158 -0.000000 0.997247 +0.074158 -0.000000 0.997247 +0.074158 -0.000000 0.997247 +-0.826561 0.000000 0.562847 +-0.826561 0.000000 0.562847 +-0.826561 0.000000 0.562847 +-0.826561 0.000000 0.562847 +-0.826561 0.000000 0.562847 +-0.826561 0.000000 0.562847 +-0.900721 0.000000 -0.434399 +-0.900721 0.000000 -0.434399 +-0.900721 0.000000 -0.434399 +-0.900721 0.000000 -0.434399 +-0.900721 0.000000 -0.434399 +-0.900721 0.000000 -0.434399 +-0.074159 0.000000 -0.997246 +-0.074159 0.000000 -0.997246 +-0.074159 0.000000 -0.997246 +-0.074159 0.000000 -0.997246 +-0.074159 0.000000 -0.997246 +-0.074159 0.000000 -0.997246 +0.826561 -0.000000 -0.562847 +0.826561 -0.000000 -0.562847 +0.826561 -0.000000 -0.562847 +0.826561 -0.000000 -0.562847 +0.826561 -0.000000 -0.562847 +0.826561 -0.000000 -0.562847 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.990034 -0.000000 0.140831 +0.990034 -0.000000 0.140831 +0.990034 -0.000000 0.140831 +0.990034 -0.000000 0.140831 +0.990034 -0.000000 0.140831 +0.990034 -0.000000 0.140831 +0.373058 -0.000000 0.927808 +0.373058 -0.000000 0.927808 +0.373058 -0.000000 0.927808 +0.373058 -0.000000 0.927808 +0.373058 -0.000000 0.927808 +0.373058 -0.000000 0.927808 +-0.616979 0.000000 0.786980 +-0.616979 0.000000 0.786980 +-0.616979 0.000000 0.786980 +-0.616979 0.000000 0.786980 +-0.616979 0.000000 0.786980 +-0.616979 0.000000 0.786980 +-0.990034 0.000000 -0.140831 +-0.990034 0.000000 -0.140831 +-0.990034 0.000000 -0.140831 +-0.990034 0.000000 -0.140831 +-0.990034 0.000000 -0.140831 +-0.990034 0.000000 -0.140831 +-0.373057 0.000000 -0.927808 +-0.373057 0.000000 -0.927808 +-0.373057 0.000000 -0.927808 +-0.373057 0.000000 -0.927808 +-0.373057 0.000000 -0.927808 +-0.373057 0.000000 -0.927808 +0.616979 -0.000000 -0.786980 +0.616979 -0.000000 -0.786980 +0.616979 -0.000000 -0.786980 +0.616979 -0.000000 -0.786980 +0.616979 -0.000000 -0.786980 +0.616979 -0.000000 -0.786980 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000003 +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.000003 +0.000000 1.000000 0.000003 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000003 +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.000003 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.707105 -0.707108 0.000002 +0.883695 -0.468063 0.000001 +0.707105 -0.707109 0.000002 +0.883695 -0.468063 0.000001 +0.707105 -0.707108 0.000002 +0.883695 -0.468063 0.000001 +-0.883695 0.468062 0.000001 +-0.707107 0.707106 0.000002 +-0.707107 0.707106 0.000002 +-0.707107 0.707106 0.000002 +-0.883695 0.468062 0.000001 +-0.883696 0.468062 0.000001 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -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.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000002 +0.052720 -0.998609 -0.000001 +-0.000000 -1.000000 -0.000002 +0.052720 -0.998609 -0.000001 +-0.000000 -1.000000 -0.000002 +0.052721 -0.998609 -0.000001 +-0.000000 0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.050030 0.998748 0.000001 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.050030 0.998748 0.000001 +0.000000 1.000000 0.000000 +-0.050031 0.998748 0.000001 +-0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +-0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +-0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +-0.906543 0.422113 0.000002 +-0.883696 0.468062 0.000001 +-0.883695 0.468062 0.000001 +-0.883696 0.468062 0.000001 +-0.906543 0.422113 0.000002 +-0.906543 0.422113 0.000002 +0.000000 -0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.906544 -0.422112 0.000002 +0.906543 -0.422112 0.000002 +0.883695 -0.468063 0.000001 +0.883695 -0.468063 0.000001 +0.883695 -0.468063 0.000001 +0.906544 -0.422112 0.000002 +0.000000 -0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.674691 0.738100 0.000003 +-0.906543 0.422113 0.000002 +-0.906543 0.422113 0.000002 +-0.906543 0.422113 0.000002 +-0.674691 0.738100 0.000003 +-0.674691 0.738100 0.000003 +-0.050030 0.998748 0.000001 +-0.050031 0.998748 0.000001 +-0.674691 0.738100 0.000003 +-0.674691 0.738100 0.000003 +-0.050031 0.998748 0.000001 +-0.674691 0.738100 0.000003 +0.674691 -0.738100 0.000004 +0.674691 -0.738100 0.000004 +0.052721 -0.998609 -0.000001 +0.052721 -0.998609 -0.000001 +0.674691 -0.738100 0.000004 +0.052720 -0.998609 -0.000001 +0.906543 -0.422112 0.000002 +0.674691 -0.738100 0.000004 +0.674691 -0.738100 0.000004 +0.674691 -0.738100 0.000004 +0.906543 -0.422112 0.000002 +0.906544 -0.422112 0.000002 +-0.000000 -0.000000 -1.000000 +-0.000000 -0.000000 -1.000000 +-0.000000 -0.000000 -1.000000 +-0.000000 -0.000000 -1.000000 +-0.000000 -0.000000 -1.000000 +-0.000000 -0.000000 -1.000000 +-0.000000 -0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-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 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.707105 -0.707108 0.000002 +-0.707105 -0.707109 0.000002 +-0.883695 -0.468063 0.000001 +-0.883695 -0.468063 0.000001 +-0.883695 -0.468063 0.000001 +-0.707105 -0.707108 0.000002 +0.883696 0.468062 0.000001 +0.707107 0.707106 0.000002 +0.883696 0.468062 0.000001 +0.707107 0.707106 0.000002 +0.883696 0.468062 0.000001 +0.707107 0.707106 0.000002 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -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.000001 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000001 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000002 +-0.052720 -0.998609 -0.000001 +-0.052721 -0.998609 -0.000001 +-0.052720 -0.998609 -0.000001 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 -0.000002 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.050031 0.998748 0.000000 +0.000000 1.000000 0.000000 +0.050030 0.998748 0.000000 +0.000000 1.000000 0.000000 +0.050030 0.998748 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.883696 0.468062 0.000001 +0.883696 0.468062 0.000001 +0.906543 0.422113 0.000002 +0.906543 0.422113 0.000002 +0.883696 0.468062 0.000001 +0.906543 0.422113 0.000002 +-0.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.906543 -0.422112 0.000002 +-0.906543 -0.422112 0.000002 +-0.883695 -0.468063 0.000001 +-0.883695 -0.468063 0.000001 +-0.906543 -0.422112 0.000002 +-0.883695 -0.468063 0.000001 +-0.000001 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.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +0.674691 0.738100 0.000003 +0.906543 0.422113 0.000002 +0.674691 0.738100 0.000003 +0.906543 0.422113 0.000002 +0.674691 0.738100 0.000003 +0.906543 0.422113 0.000002 +0.050031 0.998748 0.000000 +0.050030 0.998748 0.000000 +0.674691 0.738100 0.000003 +0.674691 0.738100 0.000003 +0.674691 0.738100 0.000003 +0.050031 0.998748 0.000000 +-0.674691 -0.738100 0.000004 +-0.674691 -0.738100 0.000004 +-0.052721 -0.998609 -0.000001 +-0.052721 -0.998609 -0.000001 +-0.052720 -0.998609 -0.000001 +-0.674691 -0.738100 0.000004 +-0.906543 -0.422112 0.000002 +-0.674691 -0.738100 0.000004 +-0.906543 -0.422112 0.000002 +-0.674691 -0.738100 0.000004 +-0.906543 -0.422112 0.000002 +-0.674691 -0.738100 0.000004 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.587784 -0.809018 +0.000001 -0.309019 -0.951056 +0.000000 -0.587784 -0.809018 +0.000001 -0.309019 -0.951056 +0.000000 -0.587784 -0.809018 +0.000001 -0.309021 -0.951055 +-0.000000 -0.809018 -0.587784 +0.000000 -0.587784 -0.809018 +-0.000000 -0.809018 -0.587784 +0.000000 -0.587784 -0.809018 +-0.000000 -0.809018 -0.587784 +0.000000 -0.587784 -0.809018 +-0.000000 -0.951056 -0.309018 +-0.000000 -0.809018 -0.587784 +-0.000000 -0.809018 -0.587784 +-0.000000 -0.809018 -0.587784 +-0.000000 -0.951056 -0.309018 +-0.000000 -0.951056 -0.309018 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951056 -0.309018 +-0.000000 -0.951056 -0.309018 +-0.000000 -0.951056 -0.309018 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951056 0.309017 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951056 0.309017 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951056 0.309017 +-0.000000 -1.000000 0.000000 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951056 0.309017 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951056 0.309017 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951056 0.309017 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.309017 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 -0.309017 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 -0.309017 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 0.000000 1.000000 +-0.000000 -0.309017 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 -0.309017 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 -0.309017 0.951056 +-0.000000 0.309018 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.309018 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.309018 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.587784 0.809018 +-0.000000 0.309018 0.951056 +-0.000000 0.587784 0.809018 +-0.000000 0.309018 0.951056 +-0.000000 0.587784 0.809018 +-0.000000 0.309018 0.951056 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +0.000000 0.951057 0.309015 +0.000000 0.809017 0.587785 +0.000000 0.809017 0.587785 +0.000000 0.809017 0.587785 +0.000000 0.951057 0.309015 +0.000000 0.951057 0.309015 +0.000000 1.000000 -0.000000 +0.000000 0.951057 0.309015 +0.000000 0.951057 0.309015 +0.000000 0.951057 0.309015 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.951057 -0.309016 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.951057 -0.309016 +0.000000 0.951057 -0.309016 +0.000000 0.951057 -0.309016 +0.000000 0.809017 -0.587785 +0.000000 0.809017 -0.587785 +0.000000 0.809017 -0.587785 +0.000000 0.951057 -0.309016 +0.000000 0.951057 -0.309016 +0.000000 0.587785 -0.809017 +0.000000 0.809017 -0.587785 +0.000000 0.587785 -0.809017 +0.000000 0.809017 -0.587785 +0.000000 0.587785 -0.809017 +0.000000 0.809017 -0.587785 +0.000001 0.309024 -0.951054 +0.000000 0.587785 -0.809017 +0.000001 0.309022 -0.951055 +0.000000 0.587785 -0.809017 +0.000001 0.309024 -0.951054 +0.000000 0.587785 -0.809017 +0.000002 -0.000000 -1.000000 +0.000001 0.309022 -0.951055 +0.000002 -0.000000 -1.000000 +0.000001 0.309022 -0.951055 +0.000002 -0.000000 -1.000000 +0.000001 0.309024 -0.951054 +0.000001 -0.309019 -0.951056 +0.000002 -0.000000 -1.000000 +0.000002 -0.000000 -1.000000 +0.000002 -0.000000 -1.000000 +0.000001 -0.309019 -0.951056 +0.000001 -0.309021 -0.951055 +-1.000000 0.000009 -0.000033 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000009 -0.000033 +-1.000000 0.000009 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.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.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -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.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.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.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.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000066 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000066 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000066 +-1.000000 -0.000000 -0.000066 +-1.000000 0.000009 -0.000033 +-1.000000 0.000009 -0.000033 +-1.000000 0.000009 -0.000033 +-1.000000 -0.000000 -0.000066 +-1.000000 -0.000000 -0.000066 +-0.067284 0.586454 0.807183 +-0.067283 0.807184 0.586453 +0.067283 0.586454 0.807183 +0.067283 0.586454 0.807183 +-0.067283 0.807184 0.586453 +0.067283 0.807184 0.586453 +0.067283 0.308317 0.948901 +-0.067284 0.586454 0.807183 +0.067283 0.586454 0.807183 +-0.067284 0.586454 0.807183 +0.067283 0.308317 0.948901 +-0.067284 0.308317 0.948901 +0.067283 -0.000000 0.997734 +-0.067284 0.308317 0.948901 +0.067283 0.308317 0.948901 +-0.067284 0.308317 0.948901 +0.067283 -0.000000 0.997734 +-0.067284 -0.000000 0.997734 +0.067283 -0.000000 0.997734 +0.067283 -0.308317 0.948901 +-0.067284 -0.000000 0.997734 +-0.067284 -0.000000 0.997734 +0.067283 -0.308317 0.948901 +-0.067284 -0.308316 0.948901 +0.067283 -0.586453 0.807184 +-0.067284 -0.308316 0.948901 +0.067283 -0.308317 0.948901 +-0.067284 -0.308316 0.948901 +0.067283 -0.586453 0.807184 +-0.067284 -0.586453 0.807184 +0.067283 -0.807184 0.586453 +-0.067284 -0.586453 0.807184 +0.067283 -0.586453 0.807184 +-0.067284 -0.586453 0.807184 +0.067283 -0.807184 0.586453 +-0.067283 -0.807184 0.586453 +0.067283 -0.807184 0.586453 +0.067283 -0.948903 0.308313 +-0.067283 -0.807184 0.586453 +-0.067283 -0.807184 0.586453 +0.067283 -0.948903 0.308313 +-0.067283 -0.948903 0.308313 +0.067283 -0.997734 -0.000000 +-0.067283 -0.948903 0.308313 +0.067283 -0.948903 0.308313 +-0.067283 -0.948903 0.308313 +0.067283 -0.997734 -0.000000 +-0.067283 -0.997734 -0.000000 +0.067283 -0.997734 -0.000000 +0.067283 -0.948903 -0.308313 +-0.067283 -0.997734 -0.000000 +-0.067283 -0.997734 -0.000000 +0.067283 -0.948903 -0.308313 +-0.067283 -0.948902 -0.308313 +0.067283 -0.807185 -0.586452 +-0.067283 -0.948902 -0.308313 +0.067283 -0.948903 -0.308313 +-0.067283 -0.948902 -0.308313 +0.067283 -0.807185 -0.586452 +-0.067283 -0.807185 -0.586452 +0.067288 -0.586461 -0.807178 +-0.067283 -0.807185 -0.586452 +0.067283 -0.807185 -0.586452 +-0.067283 -0.807185 -0.586452 +0.067288 -0.586461 -0.807178 +-0.067277 -0.586458 -0.807181 +0.067288 -0.586461 -0.807178 +0.067304 -0.308333 -0.948894 +-0.067277 -0.586458 -0.807181 +-0.067277 -0.586458 -0.807181 +0.067304 -0.308333 -0.948894 +-0.067262 -0.308325 -0.948900 +0.067304 -0.308333 -0.948894 +0.067316 0.000001 -0.997732 +-0.067262 -0.308325 -0.948900 +-0.067262 -0.308325 -0.948900 +0.067316 0.000001 -0.997732 +-0.067252 0.000001 -0.997736 +0.067316 0.000001 -0.997732 +-0.067262 0.308327 -0.948899 +-0.067252 0.000001 -0.997736 +-0.067262 0.308327 -0.948899 +0.067316 0.000001 -0.997732 +0.067305 0.308335 -0.948894 +0.067305 0.308335 -0.948894 +-0.067278 0.586456 -0.807182 +-0.067262 0.308327 -0.948899 +-0.067278 0.586456 -0.807182 +0.067305 0.308335 -0.948894 +0.067288 0.586459 -0.807179 +0.067288 0.586459 -0.807179 +0.067283 0.807184 -0.586453 +-0.067278 0.586456 -0.807182 +-0.067278 0.586456 -0.807182 +0.067283 0.807184 -0.586453 +-0.067283 0.807184 -0.586453 +-0.067283 0.948901 -0.308318 +0.067283 0.807184 -0.586453 +0.067283 0.948901 -0.308318 +0.067283 0.807184 -0.586453 +-0.067283 0.948901 -0.308318 +-0.067283 0.807184 -0.586453 +-0.067283 0.997734 -0.000000 +0.067283 0.948901 -0.308318 +0.067283 0.997734 -0.000000 +0.067283 0.948901 -0.308318 +-0.067283 0.997734 -0.000000 +-0.067283 0.948901 -0.308318 +0.067283 0.948901 0.308318 +-0.067283 0.948901 0.308318 +-0.067283 0.997734 -0.000000 +0.067283 0.948901 0.308318 +-0.067283 0.997734 -0.000000 +0.067283 0.997734 -0.000000 +0.067283 0.807184 0.586453 +-0.067283 0.807184 0.586453 +-0.067283 0.948901 0.308318 +0.067283 0.807184 0.586453 +-0.067283 0.948901 0.308318 +0.067283 0.948901 0.308318 +-0.067277 -0.586458 -0.807181 +-0.194263 -0.303131 -0.932938 +-0.194277 -0.576587 -0.793602 +-0.194263 -0.303131 -0.932938 +-0.067277 -0.586458 -0.807181 +-0.067262 -0.308325 -0.948900 +-0.194281 -0.793603 -0.576584 +-0.067277 -0.586458 -0.807181 +-0.194277 -0.576587 -0.793602 +-0.067277 -0.586458 -0.807181 +-0.194281 -0.793603 -0.576584 +-0.067283 -0.807185 -0.586452 +-0.194281 -0.932936 -0.303126 +-0.067283 -0.807185 -0.586452 +-0.194281 -0.793603 -0.576584 +-0.067283 -0.807185 -0.586452 +-0.194281 -0.932936 -0.303126 +-0.067283 -0.948902 -0.308313 +-0.194281 -0.980946 -0.000000 +-0.067283 -0.948902 -0.308313 +-0.194281 -0.932936 -0.303126 +-0.067283 -0.948902 -0.308313 +-0.194281 -0.980946 -0.000000 +-0.067283 -0.997734 -0.000000 +-0.067283 -0.948903 0.308313 +-0.194281 -0.980946 -0.000000 +-0.194281 -0.932936 0.303126 +-0.194281 -0.980946 -0.000000 +-0.067283 -0.948903 0.308313 +-0.067283 -0.997734 -0.000000 +-0.067283 -0.807184 0.586453 +-0.194281 -0.932936 0.303126 +-0.194281 -0.793602 0.576585 +-0.194281 -0.932936 0.303126 +-0.067283 -0.807184 0.586453 +-0.067283 -0.948903 0.308313 +-0.194283 -0.576585 0.793602 +-0.067283 -0.807184 0.586453 +-0.194281 -0.793602 0.576585 +-0.067283 -0.807184 0.586453 +-0.194283 -0.576585 0.793602 +-0.067284 -0.586453 0.807184 +-0.194282 -0.303129 0.932935 +-0.067284 -0.586453 0.807184 +-0.194283 -0.576585 0.793602 +-0.067284 -0.586453 0.807184 +-0.194282 -0.303129 0.932935 +-0.067284 -0.308316 0.948901 +-0.194281 -0.000000 0.980946 +-0.067284 -0.308316 0.948901 +-0.194282 -0.303129 0.932935 +-0.067284 -0.308316 0.948901 +-0.194281 -0.000000 0.980946 +-0.067284 -0.000000 0.997734 +-0.067284 0.308317 0.948901 +-0.194281 -0.000000 0.980946 +-0.194282 0.303129 0.932935 +-0.194281 -0.000000 0.980946 +-0.067284 0.308317 0.948901 +-0.067284 -0.000000 0.997734 +-0.067284 0.586454 0.807183 +-0.194282 0.303129 0.932935 +-0.194283 0.576586 0.793601 +-0.194282 0.303129 0.932935 +-0.067284 0.586454 0.807183 +-0.067284 0.308317 0.948901 +-0.067284 0.586454 0.807183 +-0.194281 0.793603 0.576584 +-0.067283 0.807184 0.586453 +-0.194281 0.793603 0.576584 +-0.067284 0.586454 0.807183 +-0.194283 0.576586 0.793601 +-0.067283 0.807184 0.586453 +-0.194280 0.932934 0.303131 +-0.067283 0.948901 0.308318 +-0.194280 0.932934 0.303131 +-0.067283 0.807184 0.586453 +-0.194281 0.793603 0.576584 +-0.067283 0.948901 0.308318 +-0.194281 0.980946 -0.000000 +-0.067283 0.997734 -0.000000 +-0.194281 0.980946 -0.000000 +-0.067283 0.948901 0.308318 +-0.194280 0.932934 0.303131 +-0.067283 0.948901 -0.308318 +-0.067283 0.997734 -0.000000 +-0.194281 0.980946 -0.000000 +-0.194281 0.980946 -0.000000 +-0.194281 0.932935 -0.303130 +-0.067283 0.948901 -0.308318 +-0.067283 0.807184 -0.586453 +-0.067283 0.948901 -0.308318 +-0.194281 0.932935 -0.303130 +-0.194281 0.932935 -0.303130 +-0.194282 0.793602 -0.576585 +-0.067283 0.807184 -0.586453 +-0.067283 0.807184 -0.586453 +-0.194282 0.793602 -0.576585 +-0.067278 0.586456 -0.807182 +-0.194282 0.793602 -0.576585 +-0.194277 0.576585 -0.793603 +-0.067278 0.586456 -0.807182 +-0.194262 0.303133 -0.932938 +-0.067278 0.586456 -0.807182 +-0.194277 0.576585 -0.793603 +-0.067278 0.586456 -0.807182 +-0.194262 0.303133 -0.932938 +-0.067262 0.308327 -0.948899 +-0.194252 0.000001 -0.980952 +-0.067262 0.308327 -0.948899 +-0.194262 0.303133 -0.932938 +-0.067262 0.308327 -0.948899 +-0.194252 0.000001 -0.980952 +-0.067252 0.000001 -0.997736 +-0.067262 -0.308325 -0.948900 +-0.194252 0.000001 -0.980952 +-0.194263 -0.303131 -0.932938 +-0.194252 0.000001 -0.980952 +-0.067262 -0.308325 -0.948900 +-0.067252 0.000001 -0.997736 +0.194282 0.576586 0.793601 +0.194283 0.303130 0.932934 +0.067283 0.586454 0.807183 +0.067283 0.586454 0.807183 +0.194283 0.303130 0.932934 +0.067283 0.308317 0.948901 +0.067283 0.308317 0.948901 +0.194282 -0.000000 0.980946 +0.067283 -0.000000 0.997734 +0.194282 -0.000000 0.980946 +0.067283 0.308317 0.948901 +0.194283 0.303130 0.932934 +0.194282 -0.000000 0.980946 +0.067283 -0.308317 0.948901 +0.067283 -0.000000 0.997734 +0.067283 -0.308317 0.948901 +0.194282 -0.000000 0.980946 +0.194284 -0.303129 0.932934 +0.194284 -0.303129 0.932934 +0.067283 -0.586453 0.807184 +0.067283 -0.308317 0.948901 +0.067283 -0.586453 0.807184 +0.194284 -0.303129 0.932934 +0.194283 -0.576585 0.793602 +0.194283 -0.576585 0.793602 +0.067283 -0.807184 0.586453 +0.067283 -0.586453 0.807184 +0.067283 -0.807184 0.586453 +0.194283 -0.576585 0.793602 +0.194280 -0.793602 0.576586 +0.067283 -0.807184 0.586453 +0.194280 -0.932936 0.303125 +0.067283 -0.948903 0.308313 +0.194280 -0.932936 0.303125 +0.067283 -0.807184 0.586453 +0.194280 -0.793602 0.576586 +0.067283 -0.948903 0.308313 +0.194280 -0.980946 -0.000000 +0.067283 -0.997734 -0.000000 +0.194280 -0.980946 -0.000000 +0.067283 -0.948903 0.308313 +0.194280 -0.932936 0.303125 +0.194280 -0.980946 -0.000000 +0.067283 -0.948903 -0.308313 +0.067283 -0.997734 -0.000000 +0.067283 -0.948903 -0.308313 +0.194280 -0.980946 -0.000000 +0.194280 -0.932936 -0.303125 +0.194280 -0.932936 -0.303125 +0.067283 -0.807185 -0.586452 +0.067283 -0.948903 -0.308313 +0.067283 -0.807185 -0.586452 +0.194280 -0.932936 -0.303125 +0.194280 -0.793603 -0.576584 +0.194280 -0.793603 -0.576584 +0.067288 -0.586461 -0.807178 +0.067283 -0.807185 -0.586452 +0.067288 -0.586461 -0.807178 +0.194280 -0.793603 -0.576584 +0.194283 -0.576595 -0.793594 +0.067288 -0.586461 -0.807178 +0.194300 -0.303149 -0.932925 +0.067304 -0.308333 -0.948894 +0.194300 -0.303149 -0.932925 +0.067288 -0.586461 -0.807178 +0.194283 -0.576595 -0.793594 +0.067304 -0.308333 -0.948894 +0.194313 0.000001 -0.980940 +0.067316 0.000001 -0.997732 +0.194313 0.000001 -0.980940 +0.067304 -0.308333 -0.948894 +0.194300 -0.303149 -0.932925 +0.194313 0.000001 -0.980940 +0.067305 0.308335 -0.948894 +0.067316 0.000001 -0.997732 +0.067305 0.308335 -0.948894 +0.194313 0.000001 -0.980940 +0.194302 0.303153 -0.932923 +0.194302 0.303153 -0.932923 +0.067288 0.586459 -0.807179 +0.067305 0.308335 -0.948894 +0.067288 0.586459 -0.807179 +0.194302 0.303153 -0.932923 +0.194286 0.576594 -0.793595 +0.194281 0.793602 -0.576586 +0.067288 0.586459 -0.807179 +0.194286 0.576594 -0.793595 +0.067288 0.586459 -0.807179 +0.194281 0.793602 -0.576586 +0.067283 0.807184 -0.586453 +0.194280 0.932935 -0.303130 +0.067283 0.807184 -0.586453 +0.194281 0.793602 -0.576586 +0.067283 0.807184 -0.586453 +0.194280 0.932935 -0.303130 +0.067283 0.948901 -0.308318 +0.194280 0.980946 -0.000000 +0.067283 0.948901 -0.308318 +0.194280 0.932935 -0.303130 +0.067283 0.948901 -0.308318 +0.194280 0.980946 -0.000000 +0.067283 0.997734 -0.000000 +0.194280 0.980946 -0.000000 +0.194280 0.932935 0.303131 +0.067283 0.948901 0.308318 +0.067283 0.948901 0.308318 +0.067283 0.997734 -0.000000 +0.194280 0.980946 -0.000000 +0.194280 0.932935 0.303131 +0.194280 0.793602 0.576585 +0.067283 0.807184 0.586453 +0.067283 0.807184 0.586453 +0.067283 0.948901 0.308318 +0.194280 0.932935 0.303131 +0.194282 0.576586 0.793601 +0.067283 0.586454 0.807183 +0.194280 0.793602 0.576585 +0.067283 0.586454 0.807183 +0.067283 0.807184 0.586453 +0.194280 0.793602 0.576585 +-0.999960 -0.000001 -0.008919 +-0.947706 -0.098634 -0.303519 +-0.999960 -0.002771 -0.008481 +-0.947706 -0.098634 -0.303519 +-0.999960 -0.000001 -0.008919 +-0.947702 -0.000000 -0.319156 +-0.999960 -0.002771 -0.008481 +-0.947713 -0.187582 -0.258172 +-0.999960 -0.005254 -0.007215 +-0.947713 -0.187582 -0.258172 +-0.999960 -0.002771 -0.008481 +-0.947706 -0.098634 -0.303519 +-0.999960 -0.007222 -0.005246 +-0.999960 -0.005254 -0.007215 +-0.947713 -0.187582 -0.258172 +-0.947713 -0.187582 -0.258172 +-0.947716 -0.258170 -0.187569 +-0.999960 -0.007222 -0.005246 +-0.947716 -0.303496 -0.098610 +-0.999960 -0.007222 -0.005246 +-0.947716 -0.258170 -0.187569 +-0.999960 -0.007222 -0.005246 +-0.947716 -0.303496 -0.098610 +-0.999960 -0.008489 -0.002759 +-0.947716 -0.319114 0.000000 +-0.999960 -0.008489 -0.002759 +-0.947716 -0.303496 -0.098610 +-0.999960 -0.008489 -0.002759 +-0.947716 -0.319114 0.000000 +-0.999960 -0.008927 0.000000 +-0.947716 -0.319114 0.000000 +-0.999960 -0.008490 0.002759 +-0.999960 -0.008927 0.000000 +-0.999960 -0.008490 0.002759 +-0.947716 -0.319114 0.000000 +-0.947716 -0.303497 0.098611 +-0.999960 -0.008490 0.002759 +-0.947715 -0.258171 0.187572 +-0.999960 -0.007222 0.005247 +-0.947715 -0.258171 0.187572 +-0.999960 -0.008490 0.002759 +-0.947716 -0.303497 0.098611 +-0.999960 -0.007222 0.005247 +-0.947715 -0.187572 0.258171 +-0.999960 -0.005247 0.007222 +-0.947715 -0.187572 0.258171 +-0.999960 -0.007222 0.005247 +-0.947715 -0.258171 0.187572 +-0.947715 -0.187572 0.258171 +-0.947715 -0.098613 0.303498 +-0.999960 -0.005247 0.007222 +-0.999960 -0.005247 0.007222 +-0.947715 -0.098613 0.303498 +-0.999960 -0.002759 0.008490 +-0.999960 -0.002759 0.008490 +-0.947715 -0.000000 0.319117 +-0.999960 -0.000000 0.008927 +-0.947715 -0.000000 0.319117 +-0.999960 -0.002759 0.008490 +-0.947715 -0.098613 0.303498 +-0.999960 0.002759 0.008490 +-0.947715 -0.000000 0.319117 +-0.947715 0.098613 0.303498 +-0.947715 -0.000000 0.319117 +-0.999960 0.002759 0.008490 +-0.999960 -0.000000 0.008927 +-0.947716 0.187572 0.258170 +-0.999960 0.002759 0.008490 +-0.947715 0.098613 0.303498 +-0.999960 0.002759 0.008490 +-0.947716 0.187572 0.258170 +-0.999960 0.005247 0.007222 +-0.999960 0.005247 0.007222 +-0.947716 0.258169 0.187571 +-0.999960 0.007222 0.005246 +-0.947716 0.258169 0.187571 +-0.999960 0.005247 0.007222 +-0.947716 0.187572 0.258170 +-0.999960 0.008490 0.002759 +-0.999960 0.007222 0.005246 +-0.947716 0.258169 0.187571 +-0.999960 0.008490 0.002759 +-0.947716 0.258169 0.187571 +-0.947717 0.303494 0.098613 +-0.999960 0.008927 0.000001 +-0.999960 0.008490 0.002759 +-0.947717 0.303494 0.098613 +-0.947717 0.303494 0.098613 +-0.947717 0.319112 0.000000 +-0.999960 0.008927 0.000001 +-0.999960 0.008491 -0.002759 +-0.999960 0.008927 0.000001 +-0.947717 0.319112 0.000000 +-0.947717 0.319112 0.000000 +-0.947717 0.303493 -0.098611 +-0.999960 0.008491 -0.002759 +-0.947717 0.258168 -0.187569 +-0.999960 0.008491 -0.002759 +-0.947717 0.303493 -0.098611 +-0.999960 0.008491 -0.002759 +-0.947717 0.258168 -0.187569 +-0.999960 0.007223 -0.005246 +-0.999960 0.005254 -0.007216 +-0.947717 0.258168 -0.187569 +-0.947713 0.187583 -0.258172 +-0.947717 0.258168 -0.187569 +-0.999960 0.005254 -0.007216 +-0.999960 0.007223 -0.005246 +-0.947713 0.187583 -0.258172 +-0.999960 0.002770 -0.008481 +-0.999960 0.005254 -0.007216 +-0.999960 0.002770 -0.008481 +-0.947713 0.187583 -0.258172 +-0.947706 0.098635 -0.303521 +-0.947706 0.098635 -0.303521 +-0.999960 -0.000001 -0.008919 +-0.999960 0.002770 -0.008481 +-0.999960 -0.000001 -0.008919 +-0.947706 0.098635 -0.303521 +-0.947702 -0.000000 -0.319156 +-0.947706 -0.098634 -0.303519 +-0.942039 -0.197209 -0.271423 +-0.947713 -0.187582 -0.258172 +-0.942039 -0.197209 -0.271423 +-0.947706 -0.098634 -0.303519 +-0.942032 -0.103696 -0.319097 +-0.942039 -0.197209 -0.271423 +-0.942043 -0.271419 -0.197196 +-0.947716 -0.258170 -0.187569 +-0.942039 -0.197209 -0.271423 +-0.947716 -0.258170 -0.187569 +-0.947713 -0.187582 -0.258172 +-0.942044 -0.319070 -0.103671 +-0.947716 -0.258170 -0.187569 +-0.942043 -0.271419 -0.197196 +-0.947716 -0.258170 -0.187569 +-0.942044 -0.319070 -0.103671 +-0.947716 -0.303496 -0.098610 +-0.942043 -0.335491 -0.000000 +-0.947716 -0.303496 -0.098610 +-0.942044 -0.319070 -0.103671 +-0.947716 -0.303496 -0.098610 +-0.942043 -0.335491 -0.000000 +-0.947716 -0.319114 0.000000 +-0.947716 -0.319114 0.000000 +-0.942043 -0.319073 0.103670 +-0.947716 -0.303497 0.098611 +-0.942043 -0.319073 0.103670 +-0.947716 -0.319114 0.000000 +-0.942043 -0.335491 -0.000000 +-0.947716 -0.303497 0.098611 +-0.942043 -0.271420 0.197198 +-0.947715 -0.258171 0.187572 +-0.942043 -0.271420 0.197198 +-0.947716 -0.303497 0.098611 +-0.942043 -0.319073 0.103670 +-0.947715 -0.258171 0.187572 +-0.942043 -0.197199 0.271420 +-0.947715 -0.187572 0.258171 +-0.942043 -0.197199 0.271420 +-0.947715 -0.258171 0.187572 +-0.942043 -0.271420 0.197198 +-0.947715 -0.187572 0.258171 +-0.942043 -0.103674 0.319073 +-0.947715 -0.098613 0.303498 +-0.942043 -0.103674 0.319073 +-0.947715 -0.187572 0.258171 +-0.942043 -0.197199 0.271420 +-0.942043 -0.103674 0.319073 +-0.942042 -0.000001 0.335494 +-0.947715 -0.000000 0.319117 +-0.942043 -0.103674 0.319073 +-0.947715 -0.000000 0.319117 +-0.947715 -0.098613 0.303498 +-0.947715 0.098613 0.303498 +-0.942042 -0.000001 0.335494 +-0.942042 0.103675 0.319073 +-0.942042 -0.000001 0.335494 +-0.947715 0.098613 0.303498 +-0.947715 -0.000000 0.319117 +-0.947716 0.187572 0.258170 +-0.942042 0.103675 0.319073 +-0.942043 0.197199 0.271418 +-0.942042 0.103675 0.319073 +-0.947716 0.187572 0.258170 +-0.947715 0.098613 0.303498 +-0.942043 0.197199 0.271418 +-0.947716 0.258169 0.187571 +-0.947716 0.187572 0.258170 +-0.947716 0.258169 0.187571 +-0.942043 0.197199 0.271418 +-0.942043 0.271419 0.197196 +-0.947717 0.303494 0.098613 +-0.947716 0.258169 0.187571 +-0.942043 0.271419 0.197196 +-0.942043 0.271419 0.197196 +-0.942044 0.319070 0.103672 +-0.947717 0.303494 0.098613 +-0.947717 0.319112 0.000000 +-0.947717 0.303494 0.098613 +-0.942044 0.319070 0.103672 +-0.942044 0.319070 0.103672 +-0.942044 0.335489 -0.000001 +-0.947717 0.319112 0.000000 +-0.942044 0.335489 -0.000001 +-0.942045 0.319067 -0.103672 +-0.947717 0.303493 -0.098611 +-0.942044 0.335489 -0.000001 +-0.947717 0.303493 -0.098611 +-0.947717 0.319112 0.000000 +-0.942045 0.319067 -0.103672 +-0.942044 0.271416 -0.197194 +-0.947717 0.258168 -0.187569 +-0.942045 0.319067 -0.103672 +-0.947717 0.258168 -0.187569 +-0.947717 0.303493 -0.098611 +-0.942040 0.197210 -0.271421 +-0.947717 0.258168 -0.187569 +-0.942044 0.271416 -0.197194 +-0.947717 0.258168 -0.187569 +-0.942040 0.197210 -0.271421 +-0.947713 0.187583 -0.258172 +-0.942032 0.103698 -0.319097 +-0.947713 0.187583 -0.258172 +-0.942040 0.197210 -0.271421 +-0.947713 0.187583 -0.258172 +-0.942032 0.103698 -0.319097 +-0.947706 0.098635 -0.303521 +-0.942032 0.103698 -0.319097 +-0.947702 -0.000000 -0.319156 +-0.947706 0.098635 -0.303521 +-0.947702 -0.000000 -0.319156 +-0.942032 0.103698 -0.319097 +-0.942028 -0.000000 -0.335535 +-0.947702 -0.000000 -0.319156 +-0.942032 -0.103696 -0.319097 +-0.947706 -0.098634 -0.303519 +-0.942032 -0.103696 -0.319097 +-0.947702 -0.000000 -0.319156 +-0.942028 -0.000000 -0.335535 +-0.999960 -0.002771 -0.008481 +-0.999960 -0.005254 -0.007215 +-1.000000 0.000000 0.000002 +-0.999960 -0.005254 -0.007215 +-0.999960 -0.007222 -0.005246 +-1.000000 0.000000 0.000002 +-0.999960 -0.007222 -0.005246 +-0.999960 -0.008489 -0.002759 +-1.000000 0.000000 0.000002 +-0.999960 -0.008489 -0.002759 +-0.999960 -0.008927 0.000000 +-1.000000 0.000000 0.000002 +-0.999960 -0.008927 0.000000 +-0.999960 -0.008490 0.002759 +-1.000000 0.000000 0.000002 +-0.999960 -0.008490 0.002759 +-0.999960 -0.007222 0.005247 +-1.000000 0.000000 0.000002 +-0.999960 -0.007222 0.005247 +-0.999960 -0.005247 0.007222 +-1.000000 0.000000 0.000002 +-0.999960 -0.005247 0.007222 +-0.999960 -0.002759 0.008490 +-1.000000 0.000000 0.000002 +-0.999960 -0.002759 0.008490 +-0.999960 -0.000000 0.008927 +-1.000000 0.000000 0.000002 +-0.999960 -0.000000 0.008927 +-0.999960 0.002759 0.008490 +-1.000000 0.000000 0.000002 +-0.999960 0.002759 0.008490 +-0.999960 0.005247 0.007222 +-1.000000 0.000000 0.000002 +-0.999960 0.005247 0.007222 +-0.999960 0.007222 0.005246 +-1.000000 0.000000 0.000002 +-0.999960 0.007222 0.005246 +-0.999960 0.008490 0.002759 +-1.000000 0.000000 0.000002 +-0.999960 0.008490 0.002759 +-0.999960 0.008927 0.000001 +-1.000000 0.000000 0.000002 +-0.999960 0.008927 0.000001 +-0.999960 0.008491 -0.002759 +-1.000000 0.000000 0.000002 +-0.999960 0.008491 -0.002759 +-0.999960 0.007223 -0.005246 +-1.000000 0.000000 0.000002 +-0.999960 0.007223 -0.005246 +-0.999960 0.005254 -0.007216 +-1.000000 0.000000 0.000002 +-0.999960 0.005254 -0.007216 +-0.999960 0.002770 -0.008481 +-1.000000 0.000000 0.000002 +-0.999960 0.002770 -0.008481 +-0.999960 -0.000001 -0.008919 +-1.000000 0.000000 0.000002 +-0.999960 -0.000001 -0.008919 +-0.999960 -0.002771 -0.008481 +-1.000000 0.000000 0.000002 +0.000001 0.309021 -0.951055 +0.000000 0.587784 -0.809018 +0.000001 0.309019 -0.951056 +0.000001 0.309019 -0.951056 +0.000000 0.587784 -0.809018 +0.000000 0.587784 -0.809018 +-0.000000 0.809018 -0.587784 +-0.000000 0.809018 -0.587784 +0.000000 0.587784 -0.809018 +-0.000000 0.809018 -0.587784 +0.000000 0.587784 -0.809018 +0.000000 0.587784 -0.809018 +-0.000000 0.951056 -0.309018 +-0.000000 0.809018 -0.587784 +-0.000000 0.951056 -0.309018 +-0.000000 0.809018 -0.587784 +-0.000000 0.951056 -0.309018 +-0.000000 0.809018 -0.587784 +0.000000 1.000000 0.000000 +-0.000000 0.951056 -0.309018 +0.000000 1.000000 0.000000 +-0.000000 0.951056 -0.309018 +0.000000 1.000000 0.000000 +-0.000000 0.951056 -0.309018 +0.000000 0.951056 0.309017 +0.000000 1.000000 0.000000 +0.000000 0.951056 0.309017 +0.000000 0.951056 0.309017 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.809017 0.587785 +0.000000 0.951056 0.309017 +0.000000 0.809017 0.587785 +0.000000 0.809017 0.587785 +0.000000 0.951056 0.309017 +0.000000 0.951056 0.309017 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +-0.000000 0.587784 0.809018 +-0.000000 0.309017 0.951056 +-0.000000 0.587784 0.809018 +-0.000000 0.587784 0.809018 +-0.000000 0.309017 0.951056 +-0.000000 0.309017 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.309017 0.951056 +-0.000000 0.309017 0.951056 +-0.000000 0.309017 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 -0.309018 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 -0.309018 0.951056 +-0.000000 -0.309018 0.951056 +-0.000000 -0.309018 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 -0.309018 0.951056 +-0.000000 -0.309018 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 -0.587784 0.809018 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.587784 0.809018 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951057 0.309016 +-0.000000 -0.809017 0.587785 +-0.000000 -0.809017 0.587785 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951057 0.309016 +-0.000000 -0.951057 0.309016 +-0.000000 -0.951057 0.309016 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951057 0.309016 +-0.000000 -0.951057 0.309016 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951057 -0.309016 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951057 -0.309016 +-0.000000 -0.951057 -0.309016 +-0.000000 -0.951057 -0.309016 +0.000000 -0.809017 -0.587785 +-0.000000 -0.951057 -0.309016 +0.000000 -0.809017 -0.587785 +-0.000000 -0.951057 -0.309016 +0.000000 -0.809017 -0.587785 +0.000000 -0.809017 -0.587785 +0.000000 -0.587786 -0.809017 +0.000000 -0.809017 -0.587785 +0.000000 -0.809017 -0.587785 +0.000000 -0.587786 -0.809017 +0.000000 -0.587786 -0.809017 +0.000000 -0.587786 -0.809017 +0.000001 -0.309024 -0.951054 +0.000000 -0.587786 -0.809017 +0.000000 -0.587786 -0.809017 +0.000001 -0.309024 -0.951054 +0.000001 -0.309022 -0.951055 +0.000001 -0.309024 -0.951054 +0.000002 -0.000000 -1.000000 +0.000001 -0.309022 -0.951055 +0.000001 -0.309022 -0.951055 +0.000002 -0.000000 -1.000000 +0.000002 -0.000000 -1.000000 +0.000002 -0.000000 -1.000000 +0.000001 0.309019 -0.951056 +0.000002 -0.000000 -1.000000 +0.000001 0.309019 -0.951056 +0.000002 -0.000000 -1.000000 +0.000001 0.309021 -0.951055 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000001 -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.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.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.000001 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000001 -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.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000008 -0.000033 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000008 -0.000033 +-1.000000 0.000000 -0.000066 +-1.000000 0.000000 -0.000066 +-1.000000 0.000000 -0.000066 +-1.000000 0.000008 -0.000033 +-1.000000 0.000008 -0.000033 +-1.000000 0.000000 -0.000066 +-1.000000 -0.000008 -0.000033 +-1.000000 0.000000 -0.000066 +-1.000000 -0.000008 -0.000033 +-1.000000 0.000000 -0.000066 +-1.000000 -0.000008 -0.000033 +-0.067285 -0.586454 0.807183 +0.067283 -0.586454 0.807183 +-0.067283 -0.807184 0.586453 +0.067283 -0.586454 0.807183 +0.067283 -0.807183 0.586454 +-0.067283 -0.807184 0.586453 +0.067283 -0.308318 0.948901 +-0.067285 -0.586454 0.807183 +-0.067284 -0.308317 0.948901 +-0.067285 -0.586454 0.807183 +0.067283 -0.308318 0.948901 +0.067283 -0.586454 0.807183 +0.067283 -0.000000 0.997734 +-0.067284 -0.308317 0.948901 +-0.067284 -0.000000 0.997734 +-0.067284 -0.308317 0.948901 +0.067283 -0.000000 0.997734 +0.067283 -0.308318 0.948901 +0.067283 0.308317 0.948901 +-0.067284 -0.000000 0.997734 +-0.067284 0.308316 0.948901 +-0.067284 -0.000000 0.997734 +0.067283 0.308317 0.948901 +0.067283 -0.000000 0.997734 +0.067283 0.586453 0.807184 +-0.067284 0.308316 0.948901 +-0.067284 0.586453 0.807184 +-0.067284 0.308316 0.948901 +0.067283 0.586453 0.807184 +0.067283 0.308317 0.948901 +0.067283 0.807184 0.586453 +-0.067284 0.586453 0.807184 +-0.067283 0.807184 0.586453 +-0.067284 0.586453 0.807184 +0.067283 0.807184 0.586453 +0.067283 0.586453 0.807184 +0.067283 0.807184 0.586453 +-0.067283 0.807184 0.586453 +0.067283 0.948903 0.308313 +-0.067283 0.807184 0.586453 +-0.067283 0.948903 0.308313 +0.067283 0.948903 0.308313 +0.067283 0.948903 0.308313 +-0.067283 0.948903 0.308313 +0.067283 0.997734 0.000000 +-0.067283 0.948903 0.308313 +-0.067283 0.997734 0.000000 +0.067283 0.997734 0.000000 +0.067283 0.997734 0.000000 +-0.067283 0.997734 0.000000 +0.067283 0.948903 -0.308313 +-0.067283 0.997734 0.000000 +-0.067283 0.948903 -0.308313 +0.067283 0.948903 -0.308313 +0.067283 0.948903 -0.308313 +-0.067283 0.948903 -0.308313 +0.067282 0.807185 -0.586451 +-0.067283 0.948903 -0.308313 +-0.067283 0.807185 -0.586452 +0.067282 0.807185 -0.586451 +0.067282 0.807185 -0.586451 +-0.067283 0.807185 -0.586452 +0.067288 0.586460 -0.807178 +-0.067283 0.807185 -0.586452 +-0.067277 0.586457 -0.807181 +0.067288 0.586460 -0.807178 +0.067304 0.308333 -0.948895 +-0.067277 0.586457 -0.807181 +-0.067262 0.308325 -0.948900 +-0.067277 0.586457 -0.807181 +0.067304 0.308333 -0.948895 +0.067288 0.586460 -0.807178 +0.067316 -0.000001 -0.997732 +-0.067262 0.308325 -0.948900 +-0.067252 -0.000001 -0.997736 +-0.067262 0.308325 -0.948900 +0.067316 -0.000001 -0.997732 +0.067304 0.308333 -0.948895 +-0.067262 -0.308328 -0.948899 +0.067316 -0.000001 -0.997732 +-0.067252 -0.000001 -0.997736 +0.067316 -0.000001 -0.997732 +-0.067262 -0.308328 -0.948899 +0.067305 -0.308335 -0.948894 +-0.067278 -0.586456 -0.807182 +0.067305 -0.308335 -0.948894 +-0.067262 -0.308328 -0.948899 +0.067305 -0.308335 -0.948894 +-0.067278 -0.586456 -0.807182 +0.067289 -0.586459 -0.807179 +-0.067283 -0.807183 -0.586454 +0.067289 -0.586459 -0.807179 +-0.067278 -0.586456 -0.807182 +0.067289 -0.586459 -0.807179 +-0.067283 -0.807183 -0.586454 +0.067283 -0.807183 -0.586454 +-0.067283 -0.948901 -0.308317 +0.067283 -0.807183 -0.586454 +-0.067283 -0.807183 -0.586454 +0.067283 -0.807183 -0.586454 +-0.067283 -0.948901 -0.308317 +0.067283 -0.948901 -0.308317 +-0.067283 -0.997734 -0.000000 +0.067283 -0.948901 -0.308317 +-0.067283 -0.948901 -0.308317 +0.067283 -0.948901 -0.308317 +-0.067283 -0.997734 -0.000000 +0.067283 -0.997734 -0.000000 +0.067283 -0.948901 0.308318 +-0.067283 -0.997734 -0.000000 +-0.067283 -0.948901 0.308318 +-0.067283 -0.997734 -0.000000 +0.067283 -0.948901 0.308318 +0.067283 -0.997734 -0.000000 +0.067283 -0.807183 0.586454 +-0.067283 -0.948901 0.308318 +-0.067283 -0.807184 0.586453 +-0.067283 -0.948901 0.308318 +0.067283 -0.807183 0.586454 +0.067283 -0.948901 0.308318 +-0.067262 0.308325 -0.948900 +-0.067277 0.586457 -0.807181 +-0.194262 0.303130 -0.932938 +-0.194262 0.303130 -0.932938 +-0.067277 0.586457 -0.807181 +-0.194276 0.576586 -0.793603 +-0.194281 0.793603 -0.576584 +-0.067277 0.586457 -0.807181 +-0.067283 0.807185 -0.586452 +-0.067277 0.586457 -0.807181 +-0.194281 0.793603 -0.576584 +-0.194276 0.576586 -0.793603 +-0.194281 0.932936 -0.303126 +-0.067283 0.807185 -0.586452 +-0.067283 0.948903 -0.308313 +-0.067283 0.807185 -0.586452 +-0.194281 0.932936 -0.303126 +-0.194281 0.793603 -0.576584 +-0.194281 0.980946 0.000000 +-0.067283 0.948903 -0.308313 +-0.067283 0.997734 0.000000 +-0.067283 0.948903 -0.308313 +-0.194281 0.980946 0.000000 +-0.194281 0.932936 -0.303126 +-0.194281 0.932936 0.303125 +-0.194281 0.980946 0.000000 +-0.067283 0.948903 0.308313 +-0.067283 0.948903 0.308313 +-0.194281 0.980946 0.000000 +-0.067283 0.997734 0.000000 +-0.194281 0.793603 0.576585 +-0.194281 0.932936 0.303125 +-0.067283 0.807184 0.586453 +-0.067283 0.807184 0.586453 +-0.194281 0.932936 0.303125 +-0.067283 0.948903 0.308313 +-0.067283 0.807184 0.586453 +-0.194282 0.576585 0.793602 +-0.194281 0.793603 0.576585 +-0.194282 0.576585 0.793602 +-0.067283 0.807184 0.586453 +-0.067284 0.586453 0.807184 +-0.067284 0.586453 0.807184 +-0.194282 0.303129 0.932935 +-0.194282 0.576585 0.793602 +-0.194282 0.303129 0.932935 +-0.067284 0.586453 0.807184 +-0.067284 0.308316 0.948901 +-0.067284 0.308316 0.948901 +-0.194281 -0.000000 0.980946 +-0.194282 0.303129 0.932935 +-0.194281 -0.000000 0.980946 +-0.067284 0.308316 0.948901 +-0.067284 -0.000000 0.997734 +-0.067284 -0.000000 0.997734 +-0.067284 -0.308317 0.948901 +-0.194281 -0.000000 0.980946 +-0.194281 -0.000000 0.980946 +-0.067284 -0.308317 0.948901 +-0.194282 -0.303129 0.932935 +-0.194282 -0.303129 0.932935 +-0.067285 -0.586454 0.807183 +-0.194283 -0.576587 0.793601 +-0.067285 -0.586454 0.807183 +-0.194282 -0.303129 0.932935 +-0.067284 -0.308317 0.948901 +-0.067285 -0.586454 0.807183 +-0.194281 -0.793602 0.576585 +-0.194283 -0.576587 0.793601 +-0.194281 -0.793602 0.576585 +-0.067285 -0.586454 0.807183 +-0.067283 -0.807184 0.586453 +-0.067283 -0.807184 0.586453 +-0.194281 -0.932935 0.303130 +-0.194281 -0.793602 0.576585 +-0.194281 -0.932935 0.303130 +-0.067283 -0.807184 0.586453 +-0.067283 -0.948901 0.308318 +-0.067283 -0.948901 0.308318 +-0.194281 -0.980946 0.000000 +-0.194281 -0.932935 0.303130 +-0.194281 -0.980946 0.000000 +-0.067283 -0.948901 0.308318 +-0.067283 -0.997734 -0.000000 +-0.067283 -0.997734 -0.000000 +-0.067283 -0.948901 -0.308317 +-0.194281 -0.980946 0.000000 +-0.194281 -0.980946 0.000000 +-0.067283 -0.948901 -0.308317 +-0.194281 -0.932935 -0.303130 +-0.067283 -0.948901 -0.308317 +-0.067283 -0.807183 -0.586454 +-0.194281 -0.932935 -0.303130 +-0.194281 -0.932935 -0.303130 +-0.067283 -0.807183 -0.586454 +-0.194282 -0.793602 -0.576586 +-0.067283 -0.807183 -0.586454 +-0.194279 -0.576586 -0.793602 +-0.194282 -0.793602 -0.576586 +-0.194279 -0.576586 -0.793602 +-0.067283 -0.807183 -0.586454 +-0.067278 -0.586456 -0.807182 +-0.067278 -0.586456 -0.807182 +-0.194263 -0.303134 -0.932937 +-0.194279 -0.576586 -0.793602 +-0.194263 -0.303134 -0.932937 +-0.067278 -0.586456 -0.807182 +-0.067262 -0.308328 -0.948899 +-0.067262 -0.308328 -0.948899 +-0.194252 -0.000001 -0.980952 +-0.194263 -0.303134 -0.932937 +-0.194252 -0.000001 -0.980952 +-0.067262 -0.308328 -0.948899 +-0.067252 -0.000001 -0.997736 +-0.067252 -0.000001 -0.997736 +-0.067262 0.308325 -0.948900 +-0.194252 -0.000001 -0.980952 +-0.194252 -0.000001 -0.980952 +-0.067262 0.308325 -0.948900 +-0.194262 0.303130 -0.932938 +0.067283 -0.586454 0.807183 +0.067283 -0.308318 0.948901 +0.194283 -0.303130 0.932934 +0.194283 -0.303130 0.932934 +0.194283 -0.576586 0.793601 +0.067283 -0.586454 0.807183 +0.194282 -0.000000 0.980946 +0.067283 -0.308318 0.948901 +0.067283 -0.000000 0.997734 +0.067283 -0.308318 0.948901 +0.194282 -0.000000 0.980946 +0.194283 -0.303130 0.932934 +0.194282 0.303129 0.932935 +0.194282 -0.000000 0.980946 +0.067283 0.308317 0.948901 +0.067283 0.308317 0.948901 +0.194282 -0.000000 0.980946 +0.067283 -0.000000 0.997734 +0.194282 0.576584 0.793603 +0.194282 0.303129 0.932935 +0.067283 0.586453 0.807184 +0.067283 0.586453 0.807184 +0.194282 0.303129 0.932935 +0.067283 0.308317 0.948901 +0.194280 0.793602 0.576586 +0.194282 0.576584 0.793603 +0.067283 0.807184 0.586453 +0.067283 0.807184 0.586453 +0.194282 0.576584 0.793603 +0.067283 0.586453 0.807184 +0.067283 0.807184 0.586453 +0.194280 0.932936 0.303125 +0.194280 0.793602 0.576586 +0.194280 0.932936 0.303125 +0.067283 0.807184 0.586453 +0.067283 0.948903 0.308313 +0.067283 0.948903 0.308313 +0.194280 0.980946 0.000000 +0.194280 0.932936 0.303125 +0.194280 0.980946 0.000000 +0.067283 0.948903 0.308313 +0.067283 0.997734 0.000000 +0.067283 0.997734 0.000000 +0.067283 0.948903 -0.308313 +0.194280 0.980946 0.000000 +0.194280 0.980946 0.000000 +0.067283 0.948903 -0.308313 +0.194280 0.932936 -0.303125 +0.067283 0.948903 -0.308313 +0.067282 0.807185 -0.586451 +0.194280 0.932936 -0.303125 +0.194280 0.932936 -0.303125 +0.067282 0.807185 -0.586451 +0.194279 0.793603 -0.576584 +0.194279 0.793603 -0.576584 +0.067282 0.807185 -0.586451 +0.067288 0.586460 -0.807178 +0.194279 0.793603 -0.576584 +0.067288 0.586460 -0.807178 +0.194283 0.576595 -0.793595 +0.194300 0.303149 -0.932924 +0.067288 0.586460 -0.807178 +0.067304 0.308333 -0.948895 +0.067288 0.586460 -0.807178 +0.194300 0.303149 -0.932924 +0.194283 0.576595 -0.793595 +0.194313 -0.000001 -0.980940 +0.067304 0.308333 -0.948895 +0.067316 -0.000001 -0.997732 +0.067304 0.308333 -0.948895 +0.194313 -0.000001 -0.980940 +0.194300 0.303149 -0.932924 +0.194302 -0.303153 -0.932923 +0.194313 -0.000001 -0.980940 +0.067305 -0.308335 -0.948894 +0.067305 -0.308335 -0.948894 +0.194313 -0.000001 -0.980940 +0.067316 -0.000001 -0.997732 +0.194287 -0.576594 -0.793594 +0.194302 -0.303153 -0.932923 +0.067289 -0.586459 -0.807179 +0.067289 -0.586459 -0.807179 +0.194302 -0.303153 -0.932923 +0.067305 -0.308335 -0.948894 +0.194281 -0.793602 -0.576586 +0.194287 -0.576594 -0.793594 +0.067283 -0.807183 -0.586454 +0.067283 -0.807183 -0.586454 +0.194287 -0.576594 -0.793594 +0.067289 -0.586459 -0.807179 +0.194280 -0.932935 -0.303129 +0.067283 -0.807183 -0.586454 +0.067283 -0.948901 -0.308317 +0.067283 -0.807183 -0.586454 +0.194280 -0.932935 -0.303129 +0.194281 -0.793602 -0.576586 +0.194280 -0.980946 0.000000 +0.067283 -0.948901 -0.308317 +0.067283 -0.997734 -0.000000 +0.067283 -0.948901 -0.308317 +0.194280 -0.980946 0.000000 +0.194280 -0.932935 -0.303129 +0.194280 -0.932935 0.303130 +0.194280 -0.980946 0.000000 +0.067283 -0.948901 0.308318 +0.067283 -0.948901 0.308318 +0.194280 -0.980946 0.000000 +0.067283 -0.997734 -0.000000 +0.194281 -0.793602 0.576586 +0.194280 -0.932935 0.303130 +0.067283 -0.807183 0.586454 +0.067283 -0.807183 0.586454 +0.194280 -0.932935 0.303130 +0.067283 -0.948901 0.308318 +0.194283 -0.576586 0.793601 +0.194281 -0.793602 0.576586 +0.067283 -0.586454 0.807183 +0.067283 -0.586454 0.807183 +0.194281 -0.793602 0.576586 +0.067283 -0.807183 0.586454 +-0.999960 0.000001 -0.008919 +-0.947706 0.098634 -0.303519 +-0.947702 0.000000 -0.319156 +-0.947706 0.098634 -0.303519 +-0.999960 0.000001 -0.008919 +-0.999960 0.002771 -0.008481 +-0.999960 0.002771 -0.008481 +-0.947713 0.187581 -0.258171 +-0.947706 0.098634 -0.303519 +-0.947713 0.187581 -0.258171 +-0.999960 0.002771 -0.008481 +-0.999960 0.005254 -0.007215 +-0.999960 0.005254 -0.007215 +-0.947716 0.258170 -0.187569 +-0.947713 0.187581 -0.258171 +-0.947716 0.258170 -0.187569 +-0.999960 0.005254 -0.007215 +-0.999960 0.007222 -0.005246 +-0.999960 0.007222 -0.005246 +-0.947717 0.303495 -0.098610 +-0.947716 0.258170 -0.187569 +-0.947717 0.303495 -0.098610 +-0.999960 0.007222 -0.005246 +-0.999960 0.008490 -0.002759 +-0.999960 0.008490 -0.002759 +-0.947716 0.319115 0.000000 +-0.947717 0.303495 -0.098610 +-0.947716 0.319115 0.000000 +-0.999960 0.008490 -0.002759 +-0.999960 0.008927 0.000000 +-0.947716 0.303498 0.098611 +-0.947716 0.319115 0.000000 +-0.999960 0.008490 0.002759 +-0.999960 0.008490 0.002759 +-0.947716 0.319115 0.000000 +-0.999960 0.008927 0.000000 +-0.999960 0.008490 0.002759 +-0.947715 0.258171 0.187573 +-0.947716 0.303498 0.098611 +-0.947715 0.258171 0.187573 +-0.999960 0.008490 0.002759 +-0.999960 0.007222 0.005247 +-0.999960 0.005247 0.007222 +-0.947715 0.258171 0.187573 +-0.999960 0.007222 0.005247 +-0.947715 0.258171 0.187573 +-0.999960 0.005247 0.007222 +-0.947715 0.187572 0.258172 +-0.947715 0.098613 0.303498 +-0.947715 0.187572 0.258172 +-0.999960 0.005247 0.007222 +-0.999960 0.005247 0.007222 +-0.999960 0.002759 0.008490 +-0.947715 0.098613 0.303498 +-0.999960 0.002759 0.008490 +-0.947715 0.000001 0.319117 +-0.947715 0.098613 0.303498 +-0.947715 0.000001 0.319117 +-0.999960 0.002759 0.008490 +-0.999960 0.000000 0.008927 +-0.999960 0.000000 0.008927 +-0.999960 -0.002759 0.008490 +-0.947715 0.000001 0.319117 +-0.947715 -0.098612 0.303498 +-0.947715 0.000001 0.319117 +-0.999960 -0.002759 0.008490 +-0.947716 -0.187571 0.258170 +-0.999960 -0.002759 0.008490 +-0.999960 -0.005247 0.007222 +-0.999960 -0.002759 0.008490 +-0.947716 -0.187571 0.258170 +-0.947715 -0.098612 0.303498 +-0.947716 -0.258168 0.187571 +-0.999960 -0.005247 0.007222 +-0.999960 -0.007222 0.005246 +-0.999960 -0.005247 0.007222 +-0.947716 -0.258168 0.187571 +-0.947716 -0.187571 0.258170 +-0.999960 -0.008490 0.002759 +-0.947716 -0.258168 0.187571 +-0.999960 -0.007222 0.005246 +-0.947716 -0.258168 0.187571 +-0.999960 -0.008490 0.002759 +-0.947717 -0.303494 0.098612 +-0.999960 -0.008927 0.000001 +-0.947717 -0.303494 0.098612 +-0.999960 -0.008490 0.002759 +-0.947717 -0.303494 0.098612 +-0.999960 -0.008927 0.000001 +-0.947717 -0.319112 0.000000 +-0.999960 -0.008491 -0.002759 +-0.947717 -0.319112 0.000000 +-0.999960 -0.008927 0.000001 +-0.947717 -0.303493 -0.098611 +-0.947717 -0.319112 0.000000 +-0.999960 -0.008491 -0.002759 +-0.999960 -0.008491 -0.002759 +-0.999960 -0.007224 -0.005246 +-0.947717 -0.303493 -0.098611 +-0.947717 -0.258168 -0.187569 +-0.947717 -0.303493 -0.098611 +-0.999960 -0.007224 -0.005246 +-0.999960 -0.007224 -0.005246 +-0.999960 -0.005254 -0.007216 +-0.947717 -0.258168 -0.187569 +-0.947713 -0.187583 -0.258172 +-0.947717 -0.258168 -0.187569 +-0.999960 -0.005254 -0.007216 +-0.947706 -0.098635 -0.303521 +-0.947713 -0.187583 -0.258172 +-0.999960 -0.002770 -0.008481 +-0.999960 -0.002770 -0.008481 +-0.947713 -0.187583 -0.258172 +-0.999960 -0.005254 -0.007216 +-0.947702 0.000000 -0.319156 +-0.947706 -0.098635 -0.303521 +-0.999960 0.000001 -0.008919 +-0.999960 0.000001 -0.008919 +-0.947706 -0.098635 -0.303521 +-0.999960 -0.002770 -0.008481 +-0.947713 0.187581 -0.258171 +-0.942032 0.103696 -0.319096 +-0.947706 0.098634 -0.303519 +-0.942032 0.103696 -0.319096 +-0.947713 0.187581 -0.258171 +-0.942039 0.197209 -0.271423 +-0.947713 0.187581 -0.258171 +-0.947716 0.258170 -0.187569 +-0.942039 0.197209 -0.271423 +-0.942043 0.271419 -0.197196 +-0.942039 0.197209 -0.271423 +-0.947716 0.258170 -0.187569 +-0.947716 0.258170 -0.187569 +-0.942044 0.319070 -0.103671 +-0.942043 0.271419 -0.197196 +-0.942044 0.319070 -0.103671 +-0.947716 0.258170 -0.187569 +-0.947717 0.303495 -0.098610 +-0.942043 0.335491 -0.000000 +-0.947717 0.303495 -0.098610 +-0.947716 0.319115 0.000000 +-0.947717 0.303495 -0.098610 +-0.942043 0.335491 -0.000000 +-0.942044 0.319070 -0.103671 +-0.942043 0.319074 0.103671 +-0.947716 0.319115 0.000000 +-0.947716 0.303498 0.098611 +-0.947716 0.319115 0.000000 +-0.942043 0.319074 0.103671 +-0.942043 0.335491 -0.000000 +-0.942042 0.271420 0.197198 +-0.947716 0.303498 0.098611 +-0.947715 0.258171 0.187573 +-0.947716 0.303498 0.098611 +-0.942042 0.271420 0.197198 +-0.942043 0.319074 0.103671 +-0.947715 0.258171 0.187573 +-0.942042 0.197199 0.271420 +-0.942042 0.271420 0.197198 +-0.942042 0.197199 0.271420 +-0.947715 0.258171 0.187573 +-0.947715 0.187572 0.258172 +-0.947715 0.187572 0.258172 +-0.942042 0.103674 0.319074 +-0.942042 0.197199 0.271420 +-0.942042 0.103674 0.319074 +-0.947715 0.187572 0.258172 +-0.947715 0.098613 0.303498 +-0.947715 0.098613 0.303498 +-0.947715 0.000001 0.319117 +-0.942042 0.103674 0.319074 +-0.942042 0.000001 0.335494 +-0.942042 0.103674 0.319074 +-0.947715 0.000001 0.319117 +-0.942042 -0.103674 0.319073 +-0.942042 0.000001 0.335494 +-0.947715 -0.098612 0.303498 +-0.942042 0.000001 0.335494 +-0.947715 0.000001 0.319117 +-0.947715 -0.098612 0.303498 +-0.942043 -0.197198 0.271418 +-0.942042 -0.103674 0.319073 +-0.947716 -0.187571 0.258170 +-0.947716 -0.187571 0.258170 +-0.942042 -0.103674 0.319073 +-0.947715 -0.098612 0.303498 +-0.942043 -0.197198 0.271418 +-0.947716 -0.258168 0.187571 +-0.942044 -0.271418 0.197196 +-0.947716 -0.258168 0.187571 +-0.942043 -0.197198 0.271418 +-0.947716 -0.187571 0.258170 +-0.947717 -0.303494 0.098612 +-0.942044 -0.271418 0.197196 +-0.947716 -0.258168 0.187571 +-0.942044 -0.271418 0.197196 +-0.947717 -0.303494 0.098612 +-0.942044 -0.319070 0.103672 +-0.947717 -0.319112 0.000000 +-0.942044 -0.319070 0.103672 +-0.947717 -0.303494 0.098612 +-0.942044 -0.319070 0.103672 +-0.947717 -0.319112 0.000000 +-0.942044 -0.335489 -0.000001 +-0.947717 -0.303493 -0.098611 +-0.942044 -0.335489 -0.000001 +-0.947717 -0.319112 0.000000 +-0.942044 -0.335489 -0.000001 +-0.947717 -0.303493 -0.098611 +-0.942045 -0.319066 -0.103672 +-0.947717 -0.303493 -0.098611 +-0.947717 -0.258168 -0.187569 +-0.942045 -0.319066 -0.103672 +-0.942044 -0.271416 -0.197195 +-0.942045 -0.319066 -0.103672 +-0.947717 -0.258168 -0.187569 +-0.942040 -0.197210 -0.271421 +-0.947717 -0.258168 -0.187569 +-0.947713 -0.187583 -0.258172 +-0.947717 -0.258168 -0.187569 +-0.942040 -0.197210 -0.271421 +-0.942044 -0.271416 -0.197195 +-0.942032 -0.103698 -0.319097 +-0.947713 -0.187583 -0.258172 +-0.947706 -0.098635 -0.303521 +-0.947713 -0.187583 -0.258172 +-0.942032 -0.103698 -0.319097 +-0.942040 -0.197210 -0.271421 +-0.942032 -0.103698 -0.319097 +-0.947702 0.000000 -0.319156 +-0.942028 -0.000000 -0.335535 +-0.947702 0.000000 -0.319156 +-0.942032 -0.103698 -0.319097 +-0.947706 -0.098635 -0.303521 +-0.947702 0.000000 -0.319156 +-0.942032 0.103696 -0.319096 +-0.942028 -0.000000 -0.335535 +-0.942032 0.103696 -0.319096 +-0.947702 0.000000 -0.319156 +-0.947706 0.098634 -0.303519 +-0.999960 0.002771 -0.008481 +-1.000000 0.000000 0.000002 +-0.999960 0.005254 -0.007215 +-0.999960 0.005254 -0.007215 +-1.000000 0.000000 0.000002 +-0.999960 0.007222 -0.005246 +-0.999960 0.007222 -0.005246 +-1.000000 0.000000 0.000002 +-0.999960 0.008490 -0.002759 +-0.999960 0.008490 -0.002759 +-1.000000 0.000000 0.000002 +-0.999960 0.008927 0.000000 +-0.999960 0.008927 0.000000 +-1.000000 0.000000 0.000002 +-0.999960 0.008490 0.002759 +-0.999960 0.008490 0.002759 +-1.000000 0.000000 0.000002 +-0.999960 0.007222 0.005247 +-0.999960 0.007222 0.005247 +-1.000000 0.000000 0.000002 +-0.999960 0.005247 0.007222 +-0.999960 0.005247 0.007222 +-1.000000 0.000000 0.000002 +-0.999960 0.002759 0.008490 +-0.999960 0.002759 0.008490 +-1.000000 0.000000 0.000002 +-0.999960 0.000000 0.008927 +-0.999960 0.000000 0.008927 +-1.000000 0.000000 0.000002 +-0.999960 -0.002759 0.008490 +-0.999960 -0.002759 0.008490 +-1.000000 0.000000 0.000002 +-0.999960 -0.005247 0.007222 +-0.999960 -0.005247 0.007222 +-1.000000 0.000000 0.000002 +-0.999960 -0.007222 0.005246 +-0.999960 -0.007222 0.005246 +-1.000000 0.000000 0.000002 +-0.999960 -0.008490 0.002759 +-0.999960 -0.008490 0.002759 +-1.000000 0.000000 0.000002 +-0.999960 -0.008927 0.000001 +-0.999960 -0.008927 0.000001 +-1.000000 0.000000 0.000002 +-0.999960 -0.008491 -0.002759 +-0.999960 -0.008491 -0.002759 +-1.000000 0.000000 0.000002 +-0.999960 -0.007224 -0.005246 +-0.999960 -0.007224 -0.005246 +-1.000000 0.000000 0.000002 +-0.999960 -0.005254 -0.007216 +-0.999960 -0.005254 -0.007216 +-1.000000 0.000000 0.000002 +-0.999960 -0.002770 -0.008481 +-0.999960 -0.002770 -0.008481 +-1.000000 0.000000 0.000002 +-0.999960 0.000001 -0.008919 +-0.999960 0.000001 -0.008919 +-1.000000 0.000000 0.000002 +-0.999960 0.002771 -0.008481 +0.000000 -0.587784 -0.809018 +-0.000001 -0.309019 -0.951056 +0.000000 -0.587784 -0.809018 +0.000000 -0.587784 -0.809018 +-0.000001 -0.309019 -0.951056 +-0.000001 -0.309021 -0.951055 +0.000000 -0.809018 -0.587784 +0.000000 -0.587784 -0.809018 +0.000000 -0.809018 -0.587784 +0.000000 -0.587784 -0.809018 +0.000000 -0.809018 -0.587784 +0.000000 -0.587784 -0.809018 +0.000000 -0.951056 -0.309018 +0.000000 -0.809018 -0.587784 +0.000000 -0.951056 -0.309018 +0.000000 -0.809018 -0.587784 +0.000000 -0.951056 -0.309018 +0.000000 -0.809018 -0.587784 +-0.000000 -1.000000 0.000000 +0.000000 -0.951056 -0.309018 +-0.000000 -1.000000 0.000000 +0.000000 -0.951056 -0.309018 +-0.000000 -1.000000 0.000000 +0.000000 -0.951056 -0.309018 +-0.000000 -0.951056 0.309017 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951056 0.309017 +-0.000000 -0.951056 0.309017 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951056 0.309017 +-0.000000 -0.809017 0.587785 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951056 0.309017 +-0.000000 -0.951056 0.309017 +-0.000000 -0.587784 0.809018 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.809017 0.587785 +-0.000000 -0.309017 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 -0.309017 0.951056 +-0.000000 -0.309017 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 -0.587784 0.809018 +-0.000000 0.000000 1.000000 +-0.000000 -0.309017 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 -0.309017 0.951056 +-0.000000 -0.309017 0.951056 +-0.000000 0.309018 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.309018 0.951056 +-0.000000 0.309018 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.587784 0.809018 +-0.000000 0.309018 0.951056 +-0.000000 0.587784 0.809018 +-0.000000 0.587784 0.809018 +-0.000000 0.309018 0.951056 +-0.000000 0.309018 0.951056 +0.000000 0.809017 0.587785 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +-0.000000 0.587784 0.809018 +0.000000 0.951057 0.309015 +0.000000 0.809017 0.587785 +0.000000 0.809017 0.587785 +0.000000 0.809017 0.587785 +0.000000 0.951057 0.309015 +0.000000 0.951057 0.309015 +0.000000 0.951057 0.309015 +0.000000 1.000000 -0.000000 +0.000000 0.951057 0.309015 +0.000000 0.951057 0.309015 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.951057 -0.309016 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.951057 -0.309016 +0.000000 0.951057 -0.309016 +0.000000 0.951057 -0.309016 +-0.000000 0.809017 -0.587785 +0.000000 0.951057 -0.309016 +-0.000000 0.809017 -0.587785 +0.000000 0.951057 -0.309016 +-0.000000 0.809017 -0.587785 +-0.000000 0.587785 -0.809017 +-0.000000 0.587785 -0.809017 +-0.000000 0.809017 -0.587785 +-0.000000 0.587785 -0.809017 +-0.000000 0.809017 -0.587785 +-0.000000 0.809017 -0.587785 +-0.000001 0.309021 -0.951055 +-0.000000 0.587785 -0.809017 +-0.000001 0.309024 -0.951054 +-0.000001 0.309024 -0.951054 +-0.000000 0.587785 -0.809017 +-0.000000 0.587785 -0.809017 +-0.000002 0.000000 -1.000000 +-0.000001 0.309021 -0.951055 +-0.000002 0.000000 -1.000000 +-0.000002 0.000000 -1.000000 +-0.000001 0.309021 -0.951055 +-0.000001 0.309024 -0.951054 +-0.000001 -0.309019 -0.951056 +-0.000002 0.000000 -1.000000 +-0.000001 -0.309021 -0.951055 +-0.000002 0.000000 -1.000000 +-0.000001 -0.309019 -0.951056 +-0.000002 0.000000 -1.000000 +1.000000 0.000008 -0.000033 +1.000000 0.000000 0.000000 +1.000000 0.000008 -0.000033 +1.000000 0.000000 0.000000 +1.000000 0.000008 -0.000033 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000001 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.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.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.000001 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000001 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.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000008 -0.000033 +1.000000 -0.000000 0.000000 +1.000000 -0.000008 -0.000033 +1.000000 -0.000008 -0.000033 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000008 -0.000033 +1.000000 -0.000000 -0.000066 +1.000000 -0.000000 -0.000066 +1.000000 -0.000000 -0.000066 +1.000000 -0.000008 -0.000033 +1.000000 -0.000008 -0.000033 +1.000000 -0.000000 -0.000066 +1.000000 0.000008 -0.000033 +1.000000 -0.000000 -0.000066 +1.000000 0.000008 -0.000033 +1.000000 -0.000000 -0.000066 +1.000000 0.000008 -0.000033 +0.067284 0.586454 0.807183 +-0.067283 0.586454 0.807183 +0.067283 0.807184 0.586453 +-0.067283 0.586454 0.807183 +-0.067283 0.807184 0.586453 +0.067283 0.807184 0.586453 +-0.067283 0.586454 0.807183 +0.067284 0.586454 0.807183 +-0.067283 0.308317 0.948901 +0.067284 0.586454 0.807183 +0.067284 0.308317 0.948901 +-0.067283 0.308317 0.948901 +-0.067283 0.308317 0.948901 +0.067284 0.308317 0.948901 +-0.067283 0.000000 0.997734 +0.067284 0.308317 0.948901 +0.067284 0.000000 0.997734 +-0.067283 0.000000 0.997734 +-0.067283 0.000000 0.997734 +0.067284 0.000000 0.997734 +-0.067283 -0.308317 0.948901 +0.067284 0.000000 0.997734 +0.067284 -0.308316 0.948901 +-0.067283 -0.308317 0.948901 +-0.067283 -0.308317 0.948901 +0.067284 -0.308316 0.948901 +-0.067283 -0.586453 0.807184 +0.067284 -0.308316 0.948901 +0.067284 -0.586453 0.807184 +-0.067283 -0.586453 0.807184 +-0.067283 -0.586453 0.807184 +0.067284 -0.586453 0.807184 +-0.067283 -0.807184 0.586453 +0.067284 -0.586453 0.807184 +0.067283 -0.807184 0.586453 +-0.067283 -0.807184 0.586453 +-0.067283 -0.807184 0.586453 +0.067283 -0.807184 0.586453 +-0.067283 -0.948903 0.308313 +0.067283 -0.807184 0.586453 +0.067283 -0.948903 0.308313 +-0.067283 -0.948903 0.308313 +-0.067283 -0.948903 0.308313 +0.067283 -0.948903 0.308313 +-0.067283 -0.997734 0.000000 +0.067283 -0.948903 0.308313 +0.067283 -0.997734 0.000000 +-0.067283 -0.997734 0.000000 +-0.067283 -0.997734 0.000000 +0.067283 -0.997734 0.000000 +-0.067283 -0.948903 -0.308313 +0.067283 -0.997734 0.000000 +0.067283 -0.948902 -0.308313 +-0.067283 -0.948903 -0.308313 +-0.067283 -0.948903 -0.308313 +0.067283 -0.948902 -0.308313 +-0.067282 -0.807185 -0.586452 +0.067283 -0.948902 -0.308313 +0.067283 -0.807185 -0.586452 +-0.067282 -0.807185 -0.586452 +-0.067282 -0.807185 -0.586452 +0.067283 -0.807185 -0.586452 +-0.067288 -0.586461 -0.807178 +0.067283 -0.807185 -0.586452 +0.067277 -0.586458 -0.807181 +-0.067288 -0.586461 -0.807178 +-0.067288 -0.586461 -0.807178 +0.067277 -0.586458 -0.807181 +-0.067304 -0.308333 -0.948894 +0.067277 -0.586458 -0.807181 +0.067262 -0.308325 -0.948900 +-0.067304 -0.308333 -0.948894 +-0.067304 -0.308333 -0.948894 +0.067262 -0.308325 -0.948900 +-0.067316 0.000001 -0.997732 +0.067262 -0.308325 -0.948900 +0.067252 0.000001 -0.997736 +-0.067316 0.000001 -0.997732 +-0.067316 0.000001 -0.997732 +0.067262 0.308327 -0.948899 +-0.067305 0.308335 -0.948894 +0.067262 0.308327 -0.948899 +-0.067316 0.000001 -0.997732 +0.067252 0.000001 -0.997736 +-0.067305 0.308335 -0.948894 +0.067278 0.586456 -0.807182 +-0.067288 0.586459 -0.807179 +0.067278 0.586456 -0.807182 +-0.067305 0.308335 -0.948894 +0.067262 0.308327 -0.948899 +-0.067288 0.586459 -0.807179 +0.067278 0.586456 -0.807182 +-0.067283 0.807184 -0.586454 +0.067278 0.586456 -0.807182 +0.067283 0.807184 -0.586453 +-0.067283 0.807184 -0.586454 +0.067283 0.948901 -0.308318 +-0.067283 0.807184 -0.586454 +0.067283 0.807184 -0.586453 +-0.067283 0.807184 -0.586454 +0.067283 0.948901 -0.308318 +-0.067283 0.948901 -0.308317 +0.067283 0.997734 -0.000000 +-0.067283 0.948901 -0.308317 +0.067283 0.948901 -0.308318 +-0.067283 0.948901 -0.308317 +0.067283 0.997734 -0.000000 +-0.067283 0.997734 -0.000000 +-0.067283 0.948901 0.308318 +0.067283 0.997734 -0.000000 +0.067283 0.948901 0.308318 +0.067283 0.997734 -0.000000 +-0.067283 0.948901 0.308318 +-0.067283 0.997734 -0.000000 +-0.067283 0.807184 0.586453 +0.067283 0.948901 0.308318 +0.067283 0.807184 0.586453 +0.067283 0.948901 0.308318 +-0.067283 0.807184 0.586453 +-0.067283 0.948901 0.308318 +0.194277 -0.576587 -0.793602 +0.194263 -0.303131 -0.932938 +0.067277 -0.586458 -0.807181 +0.067277 -0.586458 -0.807181 +0.194263 -0.303131 -0.932938 +0.067262 -0.308325 -0.948900 +0.194281 -0.793603 -0.576584 +0.067277 -0.586458 -0.807181 +0.067283 -0.807185 -0.586452 +0.067277 -0.586458 -0.807181 +0.194281 -0.793603 -0.576584 +0.194277 -0.576587 -0.793602 +0.194281 -0.932936 -0.303126 +0.067283 -0.807185 -0.586452 +0.067283 -0.948902 -0.308313 +0.067283 -0.807185 -0.586452 +0.194281 -0.932936 -0.303126 +0.194281 -0.793603 -0.576584 +0.194281 -0.980946 0.000000 +0.067283 -0.948902 -0.308313 +0.067283 -0.997734 0.000000 +0.067283 -0.948902 -0.308313 +0.194281 -0.980946 0.000000 +0.194281 -0.932936 -0.303126 +0.194281 -0.932936 0.303125 +0.194281 -0.980946 0.000000 +0.067283 -0.948903 0.308313 +0.067283 -0.948903 0.308313 +0.194281 -0.980946 0.000000 +0.067283 -0.997734 0.000000 +0.194281 -0.793603 0.576585 +0.194281 -0.932936 0.303125 +0.067283 -0.807184 0.586453 +0.067283 -0.807184 0.586453 +0.194281 -0.932936 0.303125 +0.067283 -0.948903 0.308313 +0.194283 -0.576586 0.793601 +0.067283 -0.807184 0.586453 +0.067284 -0.586453 0.807184 +0.067283 -0.807184 0.586453 +0.194283 -0.576586 0.793601 +0.194281 -0.793603 0.576585 +0.194282 -0.303129 0.932935 +0.067284 -0.586453 0.807184 +0.067284 -0.308316 0.948901 +0.067284 -0.586453 0.807184 +0.194282 -0.303129 0.932935 +0.194283 -0.576586 0.793601 +0.194281 -0.000000 0.980946 +0.067284 -0.308316 0.948901 +0.067284 0.000000 0.997734 +0.067284 -0.308316 0.948901 +0.194281 -0.000000 0.980946 +0.194282 -0.303129 0.932935 +0.194282 0.303129 0.932935 +0.194281 -0.000000 0.980946 +0.067284 0.308317 0.948901 +0.067284 0.308317 0.948901 +0.194281 -0.000000 0.980946 +0.067284 0.000000 0.997734 +0.067284 0.586454 0.807183 +0.194282 0.303129 0.932935 +0.067284 0.308317 0.948901 +0.194282 0.303129 0.932935 +0.067284 0.586454 0.807183 +0.194283 0.576586 0.793601 +0.067284 0.586454 0.807183 +0.194281 0.793603 0.576584 +0.194283 0.576586 0.793601 +0.194281 0.793603 0.576584 +0.067284 0.586454 0.807183 +0.067283 0.807184 0.586453 +0.067283 0.807184 0.586453 +0.194280 0.932935 0.303131 +0.194281 0.793603 0.576584 +0.194280 0.932935 0.303131 +0.067283 0.807184 0.586453 +0.067283 0.948901 0.308318 +0.067283 0.948901 0.308318 +0.194281 0.980946 0.000000 +0.194280 0.932935 0.303131 +0.194281 0.980946 0.000000 +0.067283 0.948901 0.308318 +0.067283 0.997734 -0.000000 +0.067283 0.997734 -0.000000 +0.067283 0.948901 -0.308318 +0.194281 0.980946 0.000000 +0.194281 0.980946 0.000000 +0.067283 0.948901 -0.308318 +0.194281 0.932935 -0.303131 +0.067283 0.948901 -0.308318 +0.067283 0.807184 -0.586453 +0.194281 0.932935 -0.303131 +0.194281 0.932935 -0.303131 +0.067283 0.807184 -0.586453 +0.194282 0.793602 -0.576585 +0.067283 0.807184 -0.586453 +0.067278 0.586456 -0.807182 +0.194282 0.793602 -0.576585 +0.194282 0.793602 -0.576585 +0.067278 0.586456 -0.807182 +0.194278 0.576585 -0.793603 +0.194262 0.303133 -0.932938 +0.067278 0.586456 -0.807182 +0.067262 0.308327 -0.948899 +0.067278 0.586456 -0.807182 +0.194262 0.303133 -0.932938 +0.194278 0.576585 -0.793603 +0.194252 0.000001 -0.980952 +0.067262 0.308327 -0.948899 +0.067252 0.000001 -0.997736 +0.067262 0.308327 -0.948899 +0.194252 0.000001 -0.980952 +0.194262 0.303133 -0.932938 +0.194263 -0.303131 -0.932938 +0.194252 0.000001 -0.980952 +0.067262 -0.308325 -0.948900 +0.067262 -0.308325 -0.948900 +0.194252 0.000001 -0.980952 +0.067252 0.000001 -0.997736 +-0.067283 0.586454 0.807183 +-0.194283 0.303130 0.932934 +-0.194282 0.576586 0.793601 +-0.194283 0.303130 0.932934 +-0.067283 0.586454 0.807183 +-0.067283 0.308317 0.948901 +-0.067283 0.308317 0.948901 +-0.194282 0.000000 0.980946 +-0.194283 0.303130 0.932934 +-0.194282 0.000000 0.980946 +-0.067283 0.308317 0.948901 +-0.067283 0.000000 0.997734 +-0.067283 0.000000 0.997734 +-0.067283 -0.308317 0.948901 +-0.194282 0.000000 0.980946 +-0.194282 0.000000 0.980946 +-0.067283 -0.308317 0.948901 +-0.194284 -0.303129 0.932934 +-0.067283 -0.308317 0.948901 +-0.067283 -0.586453 0.807184 +-0.194284 -0.303129 0.932934 +-0.194284 -0.303129 0.932934 +-0.067283 -0.586453 0.807184 +-0.194283 -0.576585 0.793602 +-0.194283 -0.576585 0.793602 +-0.067283 -0.586453 0.807184 +-0.067283 -0.807184 0.586453 +-0.194283 -0.576585 0.793602 +-0.067283 -0.807184 0.586453 +-0.194280 -0.793602 0.576586 +-0.067283 -0.807184 0.586453 +-0.194280 -0.932936 0.303125 +-0.194280 -0.793602 0.576586 +-0.194280 -0.932936 0.303125 +-0.067283 -0.807184 0.586453 +-0.067283 -0.948903 0.308313 +-0.067283 -0.948903 0.308313 +-0.194280 -0.980946 0.000000 +-0.194280 -0.932936 0.303125 +-0.194280 -0.980946 0.000000 +-0.067283 -0.948903 0.308313 +-0.067283 -0.997734 0.000000 +-0.067283 -0.997734 0.000000 +-0.067283 -0.948903 -0.308313 +-0.194280 -0.980946 0.000000 +-0.194280 -0.980946 0.000000 +-0.067283 -0.948903 -0.308313 +-0.194280 -0.932936 -0.303125 +-0.067283 -0.948903 -0.308313 +-0.067282 -0.807185 -0.586452 +-0.194280 -0.932936 -0.303125 +-0.194280 -0.932936 -0.303125 +-0.067282 -0.807185 -0.586452 +-0.194279 -0.793603 -0.576584 +-0.194279 -0.793603 -0.576584 +-0.067282 -0.807185 -0.586452 +-0.067288 -0.586461 -0.807178 +-0.194279 -0.793603 -0.576584 +-0.067288 -0.586461 -0.807178 +-0.194283 -0.576595 -0.793594 +-0.067288 -0.586461 -0.807178 +-0.194300 -0.303149 -0.932925 +-0.194283 -0.576595 -0.793594 +-0.194300 -0.303149 -0.932925 +-0.067288 -0.586461 -0.807178 +-0.067304 -0.308333 -0.948894 +-0.067304 -0.308333 -0.948894 +-0.194313 0.000001 -0.980940 +-0.194300 -0.303149 -0.932925 +-0.194313 0.000001 -0.980940 +-0.067304 -0.308333 -0.948894 +-0.067316 0.000001 -0.997732 +-0.067316 0.000001 -0.997732 +-0.067305 0.308335 -0.948894 +-0.194313 0.000001 -0.980940 +-0.194313 0.000001 -0.980940 +-0.067305 0.308335 -0.948894 +-0.194302 0.303152 -0.932923 +-0.067305 0.308335 -0.948894 +-0.067288 0.586459 -0.807179 +-0.194302 0.303152 -0.932923 +-0.194302 0.303152 -0.932923 +-0.067288 0.586459 -0.807179 +-0.194286 0.576594 -0.793595 +-0.194281 0.793602 -0.576586 +-0.067288 0.586459 -0.807179 +-0.067283 0.807184 -0.586454 +-0.067288 0.586459 -0.807179 +-0.194281 0.793602 -0.576586 +-0.194286 0.576594 -0.793595 +-0.194280 0.932935 -0.303130 +-0.067283 0.807184 -0.586454 +-0.067283 0.948901 -0.308317 +-0.067283 0.807184 -0.586454 +-0.194280 0.932935 -0.303130 +-0.194281 0.793602 -0.576586 +-0.194280 0.980946 0.000000 +-0.067283 0.948901 -0.308317 +-0.067283 0.997734 -0.000000 +-0.067283 0.948901 -0.308317 +-0.194280 0.980946 0.000000 +-0.194280 0.932935 -0.303130 +-0.194280 0.932935 0.303131 +-0.194280 0.980946 0.000000 +-0.067283 0.948901 0.308318 +-0.067283 0.948901 0.308318 +-0.194280 0.980946 0.000000 +-0.067283 0.997734 -0.000000 +-0.194280 0.793602 0.576585 +-0.194280 0.932935 0.303131 +-0.067283 0.807184 0.586453 +-0.067283 0.807184 0.586453 +-0.194280 0.932935 0.303131 +-0.067283 0.948901 0.308318 +-0.194282 0.576586 0.793601 +-0.194280 0.793602 0.576585 +-0.067283 0.586454 0.807183 +-0.067283 0.586454 0.807183 +-0.194280 0.793602 0.576585 +-0.067283 0.807184 0.586453 +0.999960 -0.000001 -0.008919 +0.947706 -0.098634 -0.303520 +0.947702 -0.000000 -0.319156 +0.947706 -0.098634 -0.303520 +0.999960 -0.000001 -0.008919 +0.999960 -0.002771 -0.008481 +0.999960 -0.002771 -0.008481 +0.947713 -0.187582 -0.258172 +0.947706 -0.098634 -0.303520 +0.947713 -0.187582 -0.258172 +0.999960 -0.002771 -0.008481 +0.999960 -0.005254 -0.007215 +0.999960 -0.005254 -0.007215 +0.999960 -0.007222 -0.005246 +0.947713 -0.187582 -0.258172 +0.947716 -0.258170 -0.187569 +0.947713 -0.187582 -0.258172 +0.999960 -0.007222 -0.005246 +0.999960 -0.007222 -0.005246 +0.947717 -0.303495 -0.098610 +0.947716 -0.258170 -0.187569 +0.947717 -0.303495 -0.098610 +0.999960 -0.007222 -0.005246 +0.999960 -0.008490 -0.002759 +0.999960 -0.008490 -0.002759 +0.947716 -0.319115 0.000000 +0.947717 -0.303495 -0.098610 +0.947716 -0.319115 0.000000 +0.999960 -0.008490 -0.002759 +0.999960 -0.008927 0.000000 +0.947716 -0.303498 0.098611 +0.947716 -0.319115 0.000000 +0.999960 -0.008490 0.002759 +0.999960 -0.008490 0.002759 +0.947716 -0.319115 0.000000 +0.999960 -0.008927 0.000000 +0.999960 -0.008490 0.002759 +0.947715 -0.258171 0.187573 +0.947716 -0.303498 0.098611 +0.947715 -0.258171 0.187573 +0.999960 -0.008490 0.002759 +0.999960 -0.007222 0.005247 +0.999960 -0.007222 0.005247 +0.947715 -0.187572 0.258171 +0.947715 -0.258171 0.187573 +0.947715 -0.187572 0.258171 +0.999960 -0.007222 0.005247 +0.999960 -0.005247 0.007222 +0.947715 -0.098613 0.303498 +0.947715 -0.187572 0.258171 +0.999960 -0.005247 0.007222 +0.999960 -0.005247 0.007222 +0.999960 -0.002759 0.008490 +0.947715 -0.098613 0.303498 +0.999960 -0.002759 0.008490 +0.947715 -0.000001 0.319117 +0.947715 -0.098613 0.303498 +0.947715 -0.000001 0.319117 +0.999960 -0.002759 0.008490 +0.999960 -0.000000 0.008927 +0.999960 -0.000000 0.008927 +0.999960 0.002759 0.008490 +0.947715 -0.000001 0.319117 +0.947715 0.098612 0.303498 +0.947715 -0.000001 0.319117 +0.999960 0.002759 0.008490 +0.947716 0.187571 0.258170 +0.999960 0.002759 0.008490 +0.999960 0.005247 0.007222 +0.999960 0.002759 0.008490 +0.947716 0.187571 0.258170 +0.947715 0.098612 0.303498 +0.947716 0.258168 0.187571 +0.999960 0.005247 0.007222 +0.999960 0.007222 0.005246 +0.999960 0.005247 0.007222 +0.947716 0.258168 0.187571 +0.947716 0.187571 0.258170 +0.999960 0.008490 0.002759 +0.947716 0.258168 0.187571 +0.999960 0.007222 0.005246 +0.947716 0.258168 0.187571 +0.999960 0.008490 0.002759 +0.947717 0.303494 0.098613 +0.999960 0.008927 0.000001 +0.947717 0.303494 0.098613 +0.999960 0.008490 0.002759 +0.947717 0.303494 0.098613 +0.999960 0.008927 0.000001 +0.947717 0.319112 0.000000 +0.999960 0.008491 -0.002759 +0.947717 0.319112 0.000000 +0.999960 0.008927 0.000001 +0.947717 0.303492 -0.098611 +0.947717 0.319112 0.000000 +0.999960 0.008491 -0.002759 +0.999960 0.008491 -0.002759 +0.947717 0.258168 -0.187569 +0.947717 0.303492 -0.098611 +0.947717 0.258168 -0.187569 +0.999960 0.008491 -0.002759 +0.999960 0.007224 -0.005246 +0.999960 0.007224 -0.005246 +0.999960 0.005254 -0.007216 +0.947717 0.258168 -0.187569 +0.947713 0.187583 -0.258172 +0.947717 0.258168 -0.187569 +0.999960 0.005254 -0.007216 +0.947706 0.098635 -0.303521 +0.947713 0.187583 -0.258172 +0.999960 0.002770 -0.008481 +0.999960 0.002770 -0.008481 +0.947713 0.187583 -0.258172 +0.999960 0.005254 -0.007216 +0.947702 -0.000000 -0.319156 +0.947706 0.098635 -0.303521 +0.999960 -0.000001 -0.008919 +0.999960 -0.000001 -0.008919 +0.947706 0.098635 -0.303521 +0.999960 0.002770 -0.008481 +0.947706 -0.098634 -0.303520 +0.942039 -0.197209 -0.271423 +0.942032 -0.103696 -0.319097 +0.942039 -0.197209 -0.271423 +0.947706 -0.098634 -0.303520 +0.947713 -0.187582 -0.258172 +0.947713 -0.187582 -0.258172 +0.947716 -0.258170 -0.187569 +0.942039 -0.197209 -0.271423 +0.942043 -0.271419 -0.197196 +0.942039 -0.197209 -0.271423 +0.947716 -0.258170 -0.187569 +0.947716 -0.258170 -0.187569 +0.942044 -0.319070 -0.103671 +0.942043 -0.271419 -0.197196 +0.942044 -0.319070 -0.103671 +0.947716 -0.258170 -0.187569 +0.947717 -0.303495 -0.098610 +0.942043 -0.335491 -0.000000 +0.947717 -0.303495 -0.098610 +0.947716 -0.319115 0.000000 +0.947717 -0.303495 -0.098610 +0.942043 -0.335491 -0.000000 +0.942044 -0.319070 -0.103671 +0.942043 -0.319074 0.103671 +0.947716 -0.319115 0.000000 +0.947716 -0.303498 0.098611 +0.947716 -0.319115 0.000000 +0.942043 -0.319074 0.103671 +0.942043 -0.335491 -0.000000 +0.942042 -0.271420 0.197198 +0.947716 -0.303498 0.098611 +0.947715 -0.258171 0.187573 +0.947716 -0.303498 0.098611 +0.942042 -0.271420 0.197198 +0.942043 -0.319074 0.103671 +0.947715 -0.258171 0.187573 +0.942042 -0.197199 0.271420 +0.942042 -0.271420 0.197198 +0.942042 -0.197199 0.271420 +0.947715 -0.258171 0.187573 +0.947715 -0.187572 0.258171 +0.947715 -0.187572 0.258171 +0.942043 -0.103674 0.319073 +0.942042 -0.197199 0.271420 +0.942043 -0.103674 0.319073 +0.947715 -0.187572 0.258171 +0.947715 -0.098613 0.303498 +0.947715 -0.098613 0.303498 +0.947715 -0.000001 0.319117 +0.942043 -0.103674 0.319073 +0.942042 -0.000001 0.335494 +0.942043 -0.103674 0.319073 +0.947715 -0.000001 0.319117 +0.942043 0.103674 0.319073 +0.942042 -0.000001 0.335494 +0.947715 0.098612 0.303498 +0.942042 -0.000001 0.335494 +0.947715 -0.000001 0.319117 +0.947715 0.098612 0.303498 +0.942043 0.197198 0.271418 +0.942043 0.103674 0.319073 +0.947716 0.187571 0.258170 +0.947716 0.187571 0.258170 +0.942043 0.103674 0.319073 +0.947715 0.098612 0.303498 +0.942043 0.197198 0.271418 +0.947716 0.258168 0.187571 +0.942044 0.271418 0.197196 +0.947716 0.258168 0.187571 +0.942043 0.197198 0.271418 +0.947716 0.187571 0.258170 +0.947717 0.303494 0.098613 +0.942044 0.271418 0.197196 +0.947716 0.258168 0.187571 +0.942044 0.271418 0.197196 +0.947717 0.303494 0.098613 +0.942044 0.319070 0.103672 +0.947717 0.319112 0.000000 +0.942044 0.319070 0.103672 +0.947717 0.303494 0.098613 +0.942044 0.319070 0.103672 +0.947717 0.319112 0.000000 +0.942044 0.335488 -0.000001 +0.947717 0.303492 -0.098611 +0.942044 0.335488 -0.000001 +0.947717 0.319112 0.000000 +0.942044 0.335488 -0.000001 +0.947717 0.303492 -0.098611 +0.942045 0.319066 -0.103672 +0.947717 0.303492 -0.098611 +0.947717 0.258168 -0.187569 +0.942045 0.319066 -0.103672 +0.942045 0.271415 -0.197194 +0.942045 0.319066 -0.103672 +0.947717 0.258168 -0.187569 +0.942040 0.197210 -0.271421 +0.947717 0.258168 -0.187569 +0.947713 0.187583 -0.258172 +0.947717 0.258168 -0.187569 +0.942040 0.197210 -0.271421 +0.942045 0.271415 -0.197194 +0.942032 0.103698 -0.319097 +0.947713 0.187583 -0.258172 +0.947706 0.098635 -0.303521 +0.947713 0.187583 -0.258172 +0.942032 0.103698 -0.319097 +0.942040 0.197210 -0.271421 +0.942032 0.103698 -0.319097 +0.947702 -0.000000 -0.319156 +0.942028 -0.000000 -0.335535 +0.947702 -0.000000 -0.319156 +0.942032 0.103698 -0.319097 +0.947706 0.098635 -0.303521 +0.947702 -0.000000 -0.319156 +0.942032 -0.103696 -0.319097 +0.942028 -0.000000 -0.335535 +0.942032 -0.103696 -0.319097 +0.947702 -0.000000 -0.319156 +0.947706 -0.098634 -0.303520 +0.999960 -0.002771 -0.008481 +1.000000 -0.000000 0.000002 +0.999960 -0.005254 -0.007215 +0.999960 -0.005254 -0.007215 +1.000000 -0.000000 0.000002 +0.999960 -0.007222 -0.005246 +0.999960 -0.007222 -0.005246 +1.000000 -0.000000 0.000002 +0.999960 -0.008490 -0.002759 +0.999960 -0.008490 -0.002759 +1.000000 -0.000000 0.000002 +0.999960 -0.008927 0.000000 +0.999960 -0.008927 0.000000 +1.000000 -0.000000 0.000002 +0.999960 -0.008490 0.002759 +0.999960 -0.008490 0.002759 +1.000000 -0.000000 0.000002 +0.999960 -0.007222 0.005247 +0.999960 -0.007222 0.005247 +1.000000 -0.000000 0.000002 +0.999960 -0.005247 0.007222 +0.999960 -0.005247 0.007222 +1.000000 -0.000000 0.000002 +0.999960 -0.002759 0.008490 +0.999960 -0.002759 0.008490 +1.000000 -0.000000 0.000002 +0.999960 -0.000000 0.008927 +0.999960 -0.000000 0.008927 +1.000000 -0.000000 0.000002 +0.999960 0.002759 0.008490 +0.999960 0.002759 0.008490 +1.000000 -0.000000 0.000002 +0.999960 0.005247 0.007222 +0.999960 0.005247 0.007222 +1.000000 -0.000000 0.000002 +0.999960 0.007222 0.005246 +0.999960 0.007222 0.005246 +1.000000 -0.000000 0.000002 +0.999960 0.008490 0.002759 +0.999960 0.008490 0.002759 +1.000000 -0.000000 0.000002 +0.999960 0.008927 0.000001 +0.999960 0.008927 0.000001 +1.000000 -0.000000 0.000002 +0.999960 0.008491 -0.002759 +0.999960 0.008491 -0.002759 +1.000000 -0.000000 0.000002 +0.999960 0.007224 -0.005246 +0.999960 0.007224 -0.005246 +1.000000 -0.000000 0.000002 +0.999960 0.005254 -0.007216 +0.999960 0.005254 -0.007216 +1.000000 -0.000000 0.000002 +0.999960 0.002770 -0.008481 +0.999960 0.002770 -0.008481 +1.000000 -0.000000 0.000002 +0.999960 -0.000001 -0.008919 +0.999960 -0.000001 -0.008919 +1.000000 -0.000000 0.000002 +0.999960 -0.002771 -0.008481 +0.000000 0.587784 -0.809018 +-0.000001 0.309021 -0.951055 +-0.000001 0.309019 -0.951056 +-0.000001 0.309019 -0.951056 +0.000000 0.587784 -0.809018 +0.000000 0.587784 -0.809018 +0.000000 0.809018 -0.587784 +0.000000 0.587784 -0.809018 +0.000000 0.587784 -0.809018 +0.000000 0.587784 -0.809018 +0.000000 0.809018 -0.587784 +0.000000 0.809018 -0.587784 +0.000000 0.951056 -0.309018 +0.000000 0.809018 -0.587784 +0.000000 0.809018 -0.587784 +0.000000 0.809018 -0.587784 +0.000000 0.951056 -0.309018 +0.000000 0.951056 -0.309018 +0.000000 1.000000 0.000000 +0.000000 0.951056 -0.309018 +0.000000 0.951056 -0.309018 +0.000000 0.951056 -0.309018 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.951056 0.309017 +0.000000 1.000000 0.000000 +0.000000 0.951056 0.309017 +0.000000 1.000000 0.000000 +0.000000 0.951056 0.309017 +0.000000 1.000000 0.000000 +0.000000 0.809017 0.587785 +0.000000 0.951056 0.309017 +0.000000 0.809017 0.587785 +0.000000 0.951056 0.309017 +0.000000 0.809017 0.587785 +0.000000 0.951056 0.309017 +0.000000 0.809017 0.587785 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +0.000000 0.809017 0.587785 +-0.000000 0.587784 0.809018 +-0.000000 0.587784 0.809018 +-0.000000 0.309017 0.951056 +-0.000000 0.587784 0.809018 +-0.000000 0.587784 0.809018 +-0.000000 0.587784 0.809018 +-0.000000 0.309017 0.951056 +-0.000000 0.309017 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.309017 0.951056 +-0.000000 0.309017 0.951056 +-0.000000 0.309017 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 -0.309018 0.951056 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 -0.309018 0.951056 +-0.000000 -0.309018 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 -0.309018 0.951056 +-0.000000 -0.309018 0.951056 +-0.000000 -0.309018 0.951056 +-0.000000 -0.587784 0.809018 +-0.000000 -0.587784 0.809018 +-0.000000 -0.587784 0.809018 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.587784 0.809018 +-0.000000 -0.809017 0.587785 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951057 0.309016 +-0.000000 -0.809017 0.587785 +-0.000000 -0.809017 0.587785 +-0.000000 -0.809017 0.587785 +-0.000000 -0.951057 0.309016 +-0.000000 -0.951057 0.309016 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951057 0.309016 +-0.000000 -0.951057 0.309016 +-0.000000 -0.951057 0.309016 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951057 -0.309016 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.951057 -0.309016 +-0.000000 -0.951057 -0.309016 +-0.000000 -0.951057 -0.309016 +-0.000000 -0.809017 -0.587785 +-0.000000 -0.809017 -0.587785 +-0.000000 -0.809017 -0.587785 +-0.000000 -0.951057 -0.309016 +-0.000000 -0.951057 -0.309016 +-0.000000 -0.809017 -0.587785 +-0.000000 -0.587786 -0.809017 +-0.000000 -0.587786 -0.809017 +-0.000000 -0.587786 -0.809017 +-0.000000 -0.809017 -0.587785 +-0.000000 -0.809017 -0.587785 +-0.000001 -0.309024 -0.951054 +-0.000000 -0.587786 -0.809017 +-0.000000 -0.587786 -0.809017 +-0.000000 -0.587786 -0.809017 +-0.000001 -0.309022 -0.951055 +-0.000001 -0.309024 -0.951054 +-0.000002 -0.000000 -1.000000 +-0.000001 -0.309024 -0.951054 +-0.000001 -0.309022 -0.951055 +-0.000001 -0.309022 -0.951055 +-0.000002 -0.000000 -1.000000 +-0.000002 -0.000000 -1.000000 +-0.000002 -0.000000 -1.000000 +-0.000001 0.309019 -0.951056 +-0.000001 0.309021 -0.951055 +-0.000001 0.309019 -0.951056 +-0.000002 -0.000000 -1.000000 +-0.000002 -0.000000 -1.000000 +1.000000 -0.000009 -0.000033 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000009 -0.000033 +1.000000 -0.000009 -0.000033 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.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.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 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.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.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.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.000001 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000008 -0.000033 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000008 -0.000033 +1.000000 0.000008 -0.000033 +1.000000 0.000008 -0.000033 +1.000000 0.000000 -0.000066 +1.000000 0.000008 -0.000033 +1.000000 0.000000 -0.000066 +1.000000 0.000008 -0.000033 +1.000000 0.000000 -0.000066 +1.000000 0.000000 -0.000066 +1.000000 -0.000009 -0.000033 +1.000000 -0.000009 -0.000033 +1.000000 -0.000009 -0.000033 +1.000000 0.000000 -0.000066 +1.000000 0.000000 -0.000066 +0.067285 -0.586454 0.807183 +0.067283 -0.807184 0.586453 +-0.067283 -0.586454 0.807183 +-0.067283 -0.586454 0.807183 +0.067283 -0.807184 0.586453 +-0.067283 -0.807183 0.586454 +-0.067283 -0.308318 0.948901 +0.067284 -0.308318 0.948901 +0.067285 -0.586454 0.807183 +-0.067283 -0.308318 0.948901 +0.067285 -0.586454 0.807183 +-0.067283 -0.586454 0.807183 +-0.067283 0.000000 0.997734 +0.067284 0.000000 0.997734 +0.067284 -0.308318 0.948901 +-0.067283 0.000000 0.997734 +0.067284 -0.308318 0.948901 +-0.067283 -0.308318 0.948901 +-0.067283 0.308317 0.948901 +0.067284 0.308316 0.948901 +0.067284 0.000000 0.997734 +-0.067283 0.308317 0.948901 +0.067284 0.000000 0.997734 +-0.067283 0.000000 0.997734 +-0.067283 0.586453 0.807184 +0.067284 0.586453 0.807184 +0.067284 0.308316 0.948901 +-0.067283 0.586453 0.807184 +0.067284 0.308316 0.948901 +-0.067283 0.308317 0.948901 +0.067283 0.807184 0.586453 +-0.067283 0.586453 0.807184 +-0.067283 0.807184 0.586453 +-0.067283 0.586453 0.807184 +0.067283 0.807184 0.586453 +0.067284 0.586453 0.807184 +-0.067283 0.807184 0.586453 +-0.067283 0.948903 0.308313 +0.067283 0.807184 0.586453 +0.067283 0.807184 0.586453 +-0.067283 0.948903 0.308313 +0.067283 0.948903 0.308313 +-0.067283 0.997734 -0.000000 +0.067283 0.948903 0.308313 +-0.067283 0.948903 0.308313 +0.067283 0.948903 0.308313 +-0.067283 0.997734 -0.000000 +0.067283 0.997734 -0.000000 +-0.067283 0.997734 -0.000000 +-0.067283 0.948903 -0.308313 +0.067283 0.997734 -0.000000 +0.067283 0.997734 -0.000000 +-0.067283 0.948903 -0.308313 +0.067283 0.948903 -0.308313 +-0.067283 0.948903 -0.308313 +-0.067283 0.807185 -0.586452 +0.067283 0.948903 -0.308313 +0.067283 0.948903 -0.308313 +-0.067283 0.807185 -0.586452 +0.067283 0.807185 -0.586452 +-0.067288 0.586460 -0.807178 +0.067283 0.807185 -0.586452 +-0.067283 0.807185 -0.586452 +0.067283 0.807185 -0.586452 +-0.067288 0.586460 -0.807178 +0.067277 0.586457 -0.807181 +-0.067304 0.308333 -0.948895 +0.067262 0.308325 -0.948900 +0.067277 0.586457 -0.807181 +-0.067304 0.308333 -0.948895 +0.067277 0.586457 -0.807181 +-0.067288 0.586460 -0.807178 +-0.067316 -0.000001 -0.997732 +0.067252 -0.000001 -0.997736 +0.067262 0.308325 -0.948900 +-0.067316 -0.000001 -0.997732 +0.067262 0.308325 -0.948900 +-0.067304 0.308333 -0.948895 +0.067262 -0.308327 -0.948899 +-0.067316 -0.000001 -0.997732 +-0.067305 -0.308335 -0.948894 +-0.067316 -0.000001 -0.997732 +0.067262 -0.308327 -0.948899 +0.067252 -0.000001 -0.997736 +0.067278 -0.586456 -0.807182 +-0.067305 -0.308335 -0.948894 +-0.067289 -0.586459 -0.807179 +-0.067305 -0.308335 -0.948894 +0.067278 -0.586456 -0.807182 +0.067262 -0.308327 -0.948899 +-0.067283 -0.807183 -0.586454 +0.067283 -0.807183 -0.586454 +0.067278 -0.586456 -0.807182 +-0.067283 -0.807183 -0.586454 +0.067278 -0.586456 -0.807182 +-0.067289 -0.586459 -0.807179 +0.067283 -0.948901 -0.308317 +-0.067283 -0.807183 -0.586454 +-0.067283 -0.948901 -0.308317 +-0.067283 -0.807183 -0.586454 +0.067283 -0.948901 -0.308317 +0.067283 -0.807183 -0.586454 +0.067283 -0.997734 -0.000000 +-0.067283 -0.948901 -0.308317 +-0.067283 -0.997734 -0.000000 +-0.067283 -0.948901 -0.308317 +0.067283 -0.997734 -0.000000 +0.067283 -0.948901 -0.308317 +-0.067283 -0.948901 0.308318 +0.067283 -0.948901 0.308318 +0.067283 -0.997734 -0.000000 +-0.067283 -0.948901 0.308318 +0.067283 -0.997734 -0.000000 +-0.067283 -0.997734 -0.000000 +-0.067283 -0.807183 0.586454 +0.067283 -0.807184 0.586453 +0.067283 -0.948901 0.308318 +-0.067283 -0.807183 0.586454 +0.067283 -0.948901 0.308318 +-0.067283 -0.948901 0.308318 +0.067277 0.586457 -0.807181 +0.067262 0.308325 -0.948900 +0.194262 0.303131 -0.932938 +0.194262 0.303131 -0.932938 +0.194276 0.576586 -0.793603 +0.067277 0.586457 -0.807181 +0.194281 0.793603 -0.576584 +0.067277 0.586457 -0.807181 +0.194276 0.576586 -0.793603 +0.067277 0.586457 -0.807181 +0.194281 0.793603 -0.576584 +0.067283 0.807185 -0.586452 +0.194281 0.932936 -0.303126 +0.067283 0.807185 -0.586452 +0.194281 0.793603 -0.576584 +0.067283 0.807185 -0.586452 +0.194281 0.932936 -0.303126 +0.067283 0.948903 -0.308313 +0.194281 0.980946 -0.000000 +0.067283 0.948903 -0.308313 +0.194281 0.932936 -0.303126 +0.067283 0.948903 -0.308313 +0.194281 0.980946 -0.000000 +0.067283 0.997734 -0.000000 +0.067283 0.948903 0.308313 +0.194281 0.980946 -0.000000 +0.194281 0.932936 0.303126 +0.194281 0.980946 -0.000000 +0.067283 0.948903 0.308313 +0.067283 0.997734 -0.000000 +0.067283 0.807184 0.586453 +0.194281 0.932936 0.303126 +0.194281 0.793602 0.576585 +0.194281 0.932936 0.303126 +0.067283 0.807184 0.586453 +0.067283 0.948903 0.308313 +0.067283 0.807184 0.586453 +0.194282 0.576585 0.793602 +0.067284 0.586453 0.807184 +0.194282 0.576585 0.793602 +0.067283 0.807184 0.586453 +0.194281 0.793602 0.576585 +0.067284 0.586453 0.807184 +0.194282 0.303129 0.932935 +0.067284 0.308316 0.948901 +0.194282 0.303129 0.932935 +0.067284 0.586453 0.807184 +0.194282 0.576585 0.793602 +0.067284 0.308316 0.948901 +0.194281 0.000000 0.980946 +0.067284 0.000000 0.997734 +0.194281 0.000000 0.980946 +0.067284 0.308316 0.948901 +0.194282 0.303129 0.932935 +0.067284 -0.308318 0.948901 +0.067284 0.000000 0.997734 +0.194281 0.000000 0.980946 +0.194281 0.000000 0.980946 +0.194282 -0.303129 0.932935 +0.067284 -0.308318 0.948901 +0.194282 -0.303129 0.932935 +0.067285 -0.586454 0.807183 +0.067284 -0.308318 0.948901 +0.067285 -0.586454 0.807183 +0.194282 -0.303129 0.932935 +0.194283 -0.576587 0.793601 +0.067285 -0.586454 0.807183 +0.194282 -0.793602 0.576585 +0.067283 -0.807184 0.586453 +0.194282 -0.793602 0.576585 +0.067285 -0.586454 0.807183 +0.194283 -0.576587 0.793601 +0.067283 -0.807184 0.586453 +0.194280 -0.932935 0.303130 +0.067283 -0.948901 0.308318 +0.194280 -0.932935 0.303130 +0.067283 -0.807184 0.586453 +0.194282 -0.793602 0.576585 +0.067283 -0.948901 0.308318 +0.194281 -0.980946 -0.000000 +0.067283 -0.997734 -0.000000 +0.194281 -0.980946 -0.000000 +0.067283 -0.948901 0.308318 +0.194280 -0.932935 0.303130 +0.067283 -0.948901 -0.308317 +0.067283 -0.997734 -0.000000 +0.194281 -0.980946 -0.000000 +0.194281 -0.980946 -0.000000 +0.194281 -0.932935 -0.303129 +0.067283 -0.948901 -0.308317 +0.067283 -0.807183 -0.586454 +0.067283 -0.948901 -0.308317 +0.194281 -0.932935 -0.303129 +0.194281 -0.932935 -0.303129 +0.194282 -0.793601 -0.576586 +0.067283 -0.807183 -0.586454 +0.067283 -0.807183 -0.586454 +0.194279 -0.576586 -0.793602 +0.067278 -0.586456 -0.807182 +0.194279 -0.576586 -0.793602 +0.067283 -0.807183 -0.586454 +0.194282 -0.793601 -0.576586 +0.067278 -0.586456 -0.807182 +0.194263 -0.303134 -0.932937 +0.067262 -0.308327 -0.948899 +0.194263 -0.303134 -0.932937 +0.067278 -0.586456 -0.807182 +0.194279 -0.576586 -0.793602 +0.067262 -0.308327 -0.948899 +0.194252 -0.000001 -0.980952 +0.067252 -0.000001 -0.997736 +0.194252 -0.000001 -0.980952 +0.067262 -0.308327 -0.948899 +0.194263 -0.303134 -0.932937 +0.067262 0.308325 -0.948900 +0.067252 -0.000001 -0.997736 +0.194252 -0.000001 -0.980952 +0.194252 -0.000001 -0.980952 +0.194262 0.303131 -0.932938 +0.067262 0.308325 -0.948900 +-0.067283 -0.308318 0.948901 +-0.067283 -0.586454 0.807183 +-0.194283 -0.303130 0.932934 +-0.194283 -0.303130 0.932934 +-0.067283 -0.586454 0.807183 +-0.194283 -0.576586 0.793601 +-0.194282 0.000000 0.980946 +-0.067283 -0.308318 0.948901 +-0.194283 -0.303130 0.932934 +-0.067283 -0.308318 0.948901 +-0.194282 0.000000 0.980946 +-0.067283 0.000000 0.997734 +-0.194282 0.000000 0.980946 +-0.194283 0.303129 0.932935 +-0.067283 0.308317 0.948901 +-0.067283 0.308317 0.948901 +-0.067283 0.000000 0.997734 +-0.194282 0.000000 0.980946 +-0.194283 0.303129 0.932935 +-0.194282 0.576584 0.793603 +-0.067283 0.586453 0.807184 +-0.067283 0.586453 0.807184 +-0.067283 0.308317 0.948901 +-0.194283 0.303129 0.932935 +-0.194280 0.793602 0.576586 +-0.067283 0.807184 0.586453 +-0.194282 0.576584 0.793603 +-0.067283 0.807184 0.586453 +-0.067283 0.586453 0.807184 +-0.194282 0.576584 0.793603 +-0.067283 0.807184 0.586453 +-0.194280 0.932936 0.303125 +-0.067283 0.948903 0.308313 +-0.194280 0.932936 0.303125 +-0.067283 0.807184 0.586453 +-0.194280 0.793602 0.576586 +-0.067283 0.948903 0.308313 +-0.194280 0.980946 -0.000000 +-0.067283 0.997734 -0.000000 +-0.194280 0.980946 -0.000000 +-0.067283 0.948903 0.308313 +-0.194280 0.932936 0.303125 +-0.194280 0.980946 -0.000000 +-0.067283 0.948903 -0.308313 +-0.067283 0.997734 -0.000000 +-0.067283 0.948903 -0.308313 +-0.194280 0.980946 -0.000000 +-0.194280 0.932936 -0.303125 +-0.194280 0.932936 -0.303125 +-0.067283 0.807185 -0.586452 +-0.067283 0.948903 -0.308313 +-0.067283 0.807185 -0.586452 +-0.194280 0.932936 -0.303125 +-0.194279 0.793603 -0.576584 +-0.194279 0.793603 -0.576584 +-0.067288 0.586460 -0.807178 +-0.067283 0.807185 -0.586452 +-0.067288 0.586460 -0.807178 +-0.194279 0.793603 -0.576584 +-0.194283 0.576594 -0.793595 +-0.194300 0.303150 -0.932924 +-0.067288 0.586460 -0.807178 +-0.194283 0.576594 -0.793595 +-0.067288 0.586460 -0.807178 +-0.194300 0.303150 -0.932924 +-0.067304 0.308333 -0.948895 +-0.194313 -0.000001 -0.980940 +-0.067304 0.308333 -0.948895 +-0.194300 0.303150 -0.932924 +-0.067304 0.308333 -0.948895 +-0.194313 -0.000001 -0.980940 +-0.067316 -0.000001 -0.997732 +-0.194313 -0.000001 -0.980940 +-0.194302 -0.303153 -0.932923 +-0.067305 -0.308335 -0.948894 +-0.067305 -0.308335 -0.948894 +-0.067316 -0.000001 -0.997732 +-0.194313 -0.000001 -0.980940 +-0.194302 -0.303153 -0.932923 +-0.194287 -0.576594 -0.793594 +-0.067289 -0.586459 -0.807179 +-0.067289 -0.586459 -0.807179 +-0.067305 -0.308335 -0.948894 +-0.194302 -0.303153 -0.932923 +-0.194281 -0.793602 -0.576586 +-0.067283 -0.807183 -0.586454 +-0.194287 -0.576594 -0.793594 +-0.067283 -0.807183 -0.586454 +-0.067289 -0.586459 -0.807179 +-0.194287 -0.576594 -0.793594 +-0.194280 -0.932935 -0.303130 +-0.067283 -0.807183 -0.586454 +-0.194281 -0.793602 -0.576586 +-0.067283 -0.807183 -0.586454 +-0.194280 -0.932935 -0.303130 +-0.067283 -0.948901 -0.308317 +-0.194280 -0.980946 -0.000000 +-0.067283 -0.948901 -0.308317 +-0.194280 -0.932935 -0.303130 +-0.067283 -0.948901 -0.308317 +-0.194280 -0.980946 -0.000000 +-0.067283 -0.997734 -0.000000 +-0.194280 -0.980946 -0.000000 +-0.194280 -0.932935 0.303131 +-0.067283 -0.948901 0.308318 +-0.067283 -0.948901 0.308318 +-0.067283 -0.997734 -0.000000 +-0.194280 -0.980946 -0.000000 +-0.194280 -0.932935 0.303131 +-0.194281 -0.793602 0.576586 +-0.067283 -0.807183 0.586454 +-0.067283 -0.807183 0.586454 +-0.067283 -0.948901 0.308318 +-0.194280 -0.932935 0.303131 +-0.194283 -0.576586 0.793601 +-0.067283 -0.807183 0.586454 +-0.194281 -0.793602 0.576586 +-0.067283 -0.807183 0.586454 +-0.194283 -0.576586 0.793601 +-0.067283 -0.586454 0.807183 +0.999960 0.000001 -0.008919 +0.947706 0.098634 -0.303519 +0.999960 0.002771 -0.008481 +0.947706 0.098634 -0.303519 +0.999960 0.000001 -0.008919 +0.947702 0.000000 -0.319156 +0.999960 0.002771 -0.008481 +0.947713 0.187582 -0.258171 +0.999960 0.005254 -0.007215 +0.947713 0.187582 -0.258171 +0.999960 0.002771 -0.008481 +0.947706 0.098634 -0.303519 +0.999960 0.005254 -0.007215 +0.947716 0.258170 -0.187569 +0.999960 0.007222 -0.005246 +0.947716 0.258170 -0.187569 +0.999960 0.005254 -0.007215 +0.947713 0.187582 -0.258171 +0.947716 0.303496 -0.098610 +0.999960 0.007222 -0.005246 +0.947716 0.258170 -0.187569 +0.999960 0.007222 -0.005246 +0.947716 0.303496 -0.098610 +0.999960 0.008489 -0.002759 +0.947716 0.319114 0.000000 +0.999960 0.008489 -0.002759 +0.947716 0.303496 -0.098610 +0.999960 0.008489 -0.002759 +0.947716 0.319114 0.000000 +0.999960 0.008927 0.000000 +0.947716 0.319114 0.000000 +0.999960 0.008490 0.002759 +0.999960 0.008927 0.000000 +0.999960 0.008490 0.002759 +0.947716 0.319114 0.000000 +0.947716 0.303497 0.098611 +0.999960 0.008490 0.002759 +0.947715 0.258171 0.187572 +0.999960 0.007222 0.005247 +0.947715 0.258171 0.187572 +0.999960 0.008490 0.002759 +0.947716 0.303497 0.098611 +0.999960 0.005247 0.007222 +0.999960 0.007222 0.005247 +0.947715 0.258171 0.187572 +0.947715 0.258171 0.187572 +0.947715 0.187572 0.258171 +0.999960 0.005247 0.007222 +0.947715 0.187572 0.258171 +0.947715 0.098613 0.303498 +0.999960 0.005247 0.007222 +0.999960 0.005247 0.007222 +0.947715 0.098613 0.303498 +0.999960 0.002759 0.008490 +0.999960 0.002759 0.008490 +0.947715 0.000000 0.319117 +0.999960 0.000000 0.008927 +0.947715 0.000000 0.319117 +0.999960 0.002759 0.008490 +0.947715 0.098613 0.303498 +0.999960 -0.002759 0.008490 +0.947715 0.000000 0.319117 +0.947715 -0.098613 0.303498 +0.947715 0.000000 0.319117 +0.999960 -0.002759 0.008490 +0.999960 0.000000 0.008927 +0.947716 -0.187573 0.258170 +0.999960 -0.002759 0.008490 +0.947715 -0.098613 0.303498 +0.999960 -0.002759 0.008490 +0.947716 -0.187573 0.258170 +0.999960 -0.005247 0.007222 +0.999960 -0.005247 0.007222 +0.947716 -0.258169 0.187571 +0.999960 -0.007222 0.005246 +0.947716 -0.258169 0.187571 +0.999960 -0.005247 0.007222 +0.947716 -0.187573 0.258170 +0.999960 -0.008490 0.002759 +0.999960 -0.007222 0.005246 +0.947716 -0.258169 0.187571 +0.999960 -0.008490 0.002759 +0.947716 -0.258169 0.187571 +0.947717 -0.303494 0.098612 +0.999960 -0.008927 0.000001 +0.999960 -0.008490 0.002759 +0.947717 -0.303494 0.098612 +0.947717 -0.303494 0.098612 +0.947717 -0.319113 0.000000 +0.999960 -0.008927 0.000001 +0.999960 -0.008490 -0.002759 +0.999960 -0.008927 0.000001 +0.947717 -0.319113 0.000000 +0.947717 -0.319113 0.000000 +0.947717 -0.303493 -0.098611 +0.999960 -0.008490 -0.002759 +0.947717 -0.303493 -0.098611 +0.947717 -0.258169 -0.187569 +0.999960 -0.007223 -0.005246 +0.947717 -0.303493 -0.098611 +0.999960 -0.007223 -0.005246 +0.999960 -0.008490 -0.002759 +0.999960 -0.005254 -0.007216 +0.947717 -0.258169 -0.187569 +0.947713 -0.187583 -0.258172 +0.947717 -0.258169 -0.187569 +0.999960 -0.005254 -0.007216 +0.999960 -0.007223 -0.005246 +0.947713 -0.187583 -0.258172 +0.999960 -0.002770 -0.008481 +0.999960 -0.005254 -0.007216 +0.999960 -0.002770 -0.008481 +0.947713 -0.187583 -0.258172 +0.947706 -0.098635 -0.303520 +0.947706 -0.098635 -0.303520 +0.999960 0.000001 -0.008919 +0.999960 -0.002770 -0.008481 +0.999960 0.000001 -0.008919 +0.947706 -0.098635 -0.303520 +0.947702 0.000000 -0.319156 +0.947713 0.187582 -0.258171 +0.947706 0.098634 -0.303519 +0.942032 0.103696 -0.319097 +0.942032 0.103696 -0.319097 +0.942039 0.197209 -0.271423 +0.947713 0.187582 -0.258171 +0.942039 0.197209 -0.271423 +0.942043 0.271419 -0.197196 +0.947716 0.258170 -0.187569 +0.942039 0.197209 -0.271423 +0.947716 0.258170 -0.187569 +0.947713 0.187582 -0.258171 +0.942044 0.319070 -0.103671 +0.947716 0.258170 -0.187569 +0.942043 0.271419 -0.197196 +0.947716 0.258170 -0.187569 +0.942044 0.319070 -0.103671 +0.947716 0.303496 -0.098610 +0.942043 0.335491 -0.000000 +0.947716 0.303496 -0.098610 +0.942044 0.319070 -0.103671 +0.947716 0.303496 -0.098610 +0.942043 0.335491 -0.000000 +0.947716 0.319114 0.000000 +0.947716 0.319114 0.000000 +0.942043 0.319073 0.103670 +0.947716 0.303497 0.098611 +0.942043 0.319073 0.103670 +0.947716 0.319114 0.000000 +0.942043 0.335491 -0.000000 +0.947716 0.303497 0.098611 +0.942043 0.271420 0.197198 +0.947715 0.258171 0.187572 +0.942043 0.271420 0.197198 +0.947716 0.303497 0.098611 +0.942043 0.319073 0.103670 +0.947715 0.258171 0.187572 +0.942043 0.197199 0.271420 +0.947715 0.187572 0.258171 +0.942043 0.197199 0.271420 +0.947715 0.258171 0.187572 +0.942043 0.271420 0.197198 +0.947715 0.187572 0.258171 +0.942042 0.103673 0.319073 +0.947715 0.098613 0.303498 +0.942042 0.103673 0.319073 +0.947715 0.187572 0.258171 +0.942043 0.197199 0.271420 +0.942042 0.103673 0.319073 +0.942042 0.000001 0.335494 +0.947715 0.000000 0.319117 +0.942042 0.103673 0.319073 +0.947715 0.000000 0.319117 +0.947715 0.098613 0.303498 +0.947715 -0.098613 0.303498 +0.942042 0.000001 0.335494 +0.942042 -0.103675 0.319073 +0.942042 0.000001 0.335494 +0.947715 -0.098613 0.303498 +0.947715 0.000000 0.319117 +0.947716 -0.187573 0.258170 +0.942042 -0.103675 0.319073 +0.942043 -0.197199 0.271418 +0.942042 -0.103675 0.319073 +0.947716 -0.187573 0.258170 +0.947715 -0.098613 0.303498 +0.942043 -0.197199 0.271418 +0.947716 -0.258169 0.187571 +0.947716 -0.187573 0.258170 +0.947716 -0.258169 0.187571 +0.942043 -0.197199 0.271418 +0.942043 -0.271419 0.197196 +0.947717 -0.303494 0.098612 +0.947716 -0.258169 0.187571 +0.942043 -0.271419 0.197196 +0.942043 -0.271419 0.197196 +0.942044 -0.319070 0.103672 +0.947717 -0.303494 0.098612 +0.947717 -0.319113 0.000000 +0.947717 -0.303494 0.098612 +0.942044 -0.319070 0.103672 +0.942044 -0.319070 0.103672 +0.942044 -0.335489 -0.000000 +0.947717 -0.319113 0.000000 +0.942044 -0.335489 -0.000000 +0.942045 -0.319067 -0.103672 +0.947717 -0.303493 -0.098611 +0.942044 -0.335489 -0.000000 +0.947717 -0.303493 -0.098611 +0.947717 -0.319113 0.000000 +0.942045 -0.319067 -0.103672 +0.942044 -0.271416 -0.197195 +0.947717 -0.258169 -0.187569 +0.942045 -0.319067 -0.103672 +0.947717 -0.258169 -0.187569 +0.947717 -0.303493 -0.098611 +0.942040 -0.197210 -0.271421 +0.947717 -0.258169 -0.187569 +0.942044 -0.271416 -0.197195 +0.947717 -0.258169 -0.187569 +0.942040 -0.197210 -0.271421 +0.947713 -0.187583 -0.258172 +0.942032 -0.103698 -0.319097 +0.947713 -0.187583 -0.258172 +0.942040 -0.197210 -0.271421 +0.947713 -0.187583 -0.258172 +0.942032 -0.103698 -0.319097 +0.947706 -0.098635 -0.303520 +0.942032 -0.103698 -0.319097 +0.947702 0.000000 -0.319156 +0.947706 -0.098635 -0.303520 +0.947702 0.000000 -0.319156 +0.942032 -0.103698 -0.319097 +0.942028 -0.000000 -0.335535 +0.947702 0.000000 -0.319156 +0.942032 0.103696 -0.319097 +0.947706 0.098634 -0.303519 +0.942032 0.103696 -0.319097 +0.947702 0.000000 -0.319156 +0.942028 -0.000000 -0.335535 +0.999960 0.002771 -0.008481 +0.999960 0.005254 -0.007215 +1.000000 -0.000000 0.000002 +0.999960 0.005254 -0.007215 +0.999960 0.007222 -0.005246 +1.000000 -0.000000 0.000002 +0.999960 0.007222 -0.005246 +0.999960 0.008489 -0.002759 +1.000000 -0.000000 0.000002 +0.999960 0.008489 -0.002759 +0.999960 0.008927 0.000000 +1.000000 -0.000000 0.000002 +0.999960 0.008927 0.000000 +0.999960 0.008490 0.002759 +1.000000 -0.000000 0.000002 +0.999960 0.008490 0.002759 +0.999960 0.007222 0.005247 +1.000000 -0.000000 0.000002 +0.999960 0.007222 0.005247 +0.999960 0.005247 0.007222 +1.000000 -0.000000 0.000002 +0.999960 0.005247 0.007222 +0.999960 0.002759 0.008490 +1.000000 -0.000000 0.000002 +0.999960 0.002759 0.008490 +0.999960 0.000000 0.008927 +1.000000 -0.000000 0.000002 +0.999960 0.000000 0.008927 +0.999960 -0.002759 0.008490 +1.000000 -0.000000 0.000002 +0.999960 -0.002759 0.008490 +0.999960 -0.005247 0.007222 +1.000000 -0.000000 0.000002 +0.999960 -0.005247 0.007222 +0.999960 -0.007222 0.005246 +1.000000 -0.000000 0.000002 +0.999960 -0.007222 0.005246 +0.999960 -0.008490 0.002759 +1.000000 -0.000000 0.000002 +0.999960 -0.008490 0.002759 +0.999960 -0.008927 0.000001 +1.000000 -0.000000 0.000002 +0.999960 -0.008927 0.000001 +0.999960 -0.008490 -0.002759 +1.000000 -0.000000 0.000002 +0.999960 -0.008490 -0.002759 +0.999960 -0.007223 -0.005246 +1.000000 -0.000000 0.000002 +0.999960 -0.007223 -0.005246 +0.999960 -0.005254 -0.007216 +1.000000 -0.000000 0.000002 +0.999960 -0.005254 -0.007216 +0.999960 -0.002770 -0.008481 +1.000000 -0.000000 0.000002 +0.999960 -0.002770 -0.008481 +0.999960 0.000001 -0.008919 +1.000000 -0.000000 0.000002 +0.999960 0.000001 -0.008919 +0.999960 0.002771 -0.008481 +1.000000 -0.000000 0.000002 +0.000000 0.309017 -0.951057 +-0.257294 0.781779 -0.567998 +-0.257294 0.298613 -0.919037 +-0.257294 0.781779 -0.567998 +0.000000 0.309017 -0.951057 +0.000000 0.809016 -0.587786 +0.000000 -0.309017 -0.951057 +-0.257294 0.298613 -0.919037 +-0.257294 -0.298614 -0.919037 +-0.257294 0.298613 -0.919037 +0.000000 -0.309017 -0.951057 +0.000000 0.309017 -0.951057 +-0.000000 -0.809016 -0.587786 +-0.257294 -0.298614 -0.919037 +-0.257294 -0.781780 -0.567996 +-0.257294 -0.298614 -0.919037 +-0.000000 -0.809016 -0.587786 +0.000000 -0.309017 -0.951057 +-0.000000 -1.000000 0.000000 +-0.257294 -0.781780 -0.567996 +-0.257295 -0.966333 0.000000 +-0.257294 -0.781780 -0.567996 +-0.000000 -1.000000 0.000000 +-0.000000 -0.809016 -0.587786 +-0.000000 -0.809016 0.587786 +-0.257295 -0.966333 0.000000 +-0.257295 -0.781780 0.567997 +-0.257295 -0.966333 0.000000 +-0.000000 -0.809016 0.587786 +-0.000000 -1.000000 0.000000 +-0.000000 -0.309017 0.951057 +-0.257295 -0.781780 0.567997 +-0.257294 -0.298614 0.919037 +-0.257295 -0.781780 0.567997 +-0.000000 -0.309017 0.951057 +-0.000000 -0.809016 0.587786 +-0.000000 0.309017 0.951057 +-0.257294 -0.298614 0.919037 +-0.257293 0.298614 0.919037 +-0.257294 -0.298614 0.919037 +-0.000000 0.309017 0.951057 +-0.000000 -0.309017 0.951057 +0.000000 0.809016 0.587786 +-0.257293 0.298614 0.919037 +-0.257294 0.781779 0.567997 +-0.257293 0.298614 0.919037 +0.000000 0.809016 0.587786 +-0.000000 0.309017 0.951057 +0.000000 0.809016 0.587786 +-0.257294 0.781779 0.567997 +0.000000 1.000000 0.000000 +-0.257294 0.781779 0.567997 +-0.257294 0.966333 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.257294 0.966333 -0.000000 +0.000000 0.809016 -0.587786 +-0.257294 0.966333 -0.000000 +-0.257294 0.781779 -0.567998 +0.000000 0.809016 -0.587786 +-0.946007 0.324145 -0.000000 +-0.946007 -0.324145 0.000000 +-0.956045 -0.148068 0.253089 +-0.946007 0.324145 -0.000000 +-0.956045 -0.148068 0.253089 +-0.956045 0.148067 0.253088 +-0.044018 0.808232 0.587217 +-0.044018 0.808232 0.587217 +-0.044018 0.308718 0.950135 +-0.044018 0.308718 0.950134 +-0.044018 0.308718 0.950135 +-0.044018 0.808232 0.587217 +-0.044019 0.999031 -0.000000 +-0.044018 0.808232 0.587217 +-0.044018 0.808232 0.587217 +-0.044018 0.808232 0.587217 +-0.044019 0.999031 -0.000000 +-0.044019 0.999031 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.044018 0.808231 -0.587217 +-0.044019 0.999031 -0.000000 +-0.044018 0.808231 -0.587217 +-0.044019 0.999031 -0.000000 +-0.044018 0.808231 -0.587217 +-0.044019 0.999031 -0.000000 +-0.044018 -0.308718 0.950135 +-0.044018 -0.808231 0.587217 +-0.044018 -0.808232 0.587218 +-0.044018 -0.808231 0.587217 +-0.044018 -0.308718 0.950135 +-0.044018 -0.308718 0.950135 +-0.044017 0.308718 -0.950135 +-0.044018 0.808231 -0.587217 +-0.044018 0.808231 -0.587217 +-0.044018 0.808231 -0.587217 +-0.044017 0.308718 -0.950135 +-0.044017 0.308718 -0.950135 +-0.044018 -0.808232 0.587218 +-0.044018 -0.808231 0.587217 +-0.044019 -0.999031 0.000000 +-0.044019 -0.999031 0.000000 +-0.044019 -0.999031 0.000000 +-0.044018 -0.808231 0.587217 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.044018 -0.808232 -0.587217 +-0.044019 -0.999031 0.000000 +-0.044019 -0.999031 0.000000 +-0.044019 -0.999031 0.000000 +-0.044018 -0.808232 -0.587217 +-0.044018 -0.808232 -0.587217 +-0.044018 -0.808232 -0.587217 +-0.044018 -0.808232 -0.587217 +-0.044017 -0.308718 -0.950135 +-0.044017 -0.308718 -0.950135 +-0.044017 -0.308718 -0.950135 +-0.044018 -0.808232 -0.587217 +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 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.044018 -0.308718 0.950135 +-0.044018 0.308718 0.950135 +-0.044018 -0.308718 0.950135 +-0.044018 -0.308718 0.950135 +-0.044018 0.308718 0.950135 +-0.044018 0.308718 0.950134 +-0.044017 0.308718 -0.950135 +-0.044017 -0.308718 -0.950135 +-0.044017 0.308718 -0.950135 +-0.044017 0.308718 -0.950135 +-0.044017 -0.308718 -0.950135 +-0.044017 -0.308718 -0.950135 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000002 -0.000000 +-0.658954 0.232438 -0.715369 +-0.257294 0.781779 -0.567998 +-0.658955 0.608528 -0.442123 +-0.257294 0.781779 -0.567998 +-0.658954 0.232438 -0.715369 +-0.257294 0.298613 -0.919037 +-0.658957 0.752181 -0.000000 +-0.257294 0.781779 -0.567998 +-0.257294 0.966333 -0.000000 +-0.658957 0.752181 -0.000000 +-0.658955 0.608528 -0.442123 +-0.257294 0.781779 -0.567998 +-0.257294 0.781779 0.567997 +-0.658957 0.752181 -0.000000 +-0.257294 0.966333 -0.000000 +-0.658957 0.752181 -0.000000 +-0.257294 0.781779 0.567997 +-0.658954 0.608529 0.442122 +-0.658953 0.232439 0.715369 +-0.658954 0.608529 0.442122 +-0.257294 0.781779 0.567997 +-0.257294 0.781779 0.567997 +-0.257293 0.298614 0.919037 +-0.658953 0.232439 0.715369 +-0.658955 -0.232439 0.715367 +-0.658953 0.232439 0.715369 +-0.257293 0.298614 0.919037 +-0.257293 0.298614 0.919037 +-0.257294 -0.298614 0.919037 +-0.658955 -0.232439 0.715367 +-0.257295 -0.781780 0.567997 +-0.658955 -0.232439 0.715367 +-0.257294 -0.298614 0.919037 +-0.658955 -0.232439 0.715367 +-0.257295 -0.781780 0.567997 +-0.658956 -0.608528 0.442120 +-0.658957 -0.752181 0.000000 +-0.658956 -0.608528 0.442120 +-0.257295 -0.781780 0.567997 +-0.257295 -0.781780 0.567997 +-0.257295 -0.966333 0.000000 +-0.658957 -0.752181 0.000000 +-0.658957 -0.752181 0.000000 +-0.257294 -0.781780 -0.567996 +-0.658955 -0.608530 -0.442119 +-0.257294 -0.781780 -0.567996 +-0.658957 -0.752181 0.000000 +-0.257295 -0.966333 0.000000 +-0.658956 -0.232440 -0.715366 +-0.658955 -0.608530 -0.442119 +-0.257294 -0.781780 -0.567996 +-0.658956 -0.232440 -0.715366 +-0.257294 -0.781780 -0.567996 +-0.257294 -0.298614 -0.919037 +-0.658954 0.232438 -0.715369 +-0.658956 -0.232440 -0.715366 +-0.257294 -0.298614 -0.919037 +-0.257294 -0.298614 -0.919037 +-0.257294 0.298613 -0.919037 +-0.658954 0.232438 -0.715369 +-1.000000 -0.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000001 -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.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.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 -0.000002 -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.000001 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000001 -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.000000 -0.000000 +-1.000000 0.000001 -0.000000 +-0.995969 0.076438 -0.046936 +-1.000000 0.000003 -0.000000 +-0.995969 0.076438 -0.046936 +-1.000000 0.000001 -0.000000 +-0.995568 0.014660 -0.092899 +-1.000000 0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-0.995568 -0.014660 -0.092898 +-1.000000 0.000001 -0.000000 +-0.995568 -0.014660 -0.092898 +-0.995568 0.014660 -0.092899 +-0.995568 -0.014660 -0.092898 +-1.000000 -0.000001 -0.000000 +-0.995969 -0.076438 -0.046936 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000003 -0.000000 +-0.995969 -0.076438 -0.046936 +-1.000000 -0.000003 -0.000000 +-0.995969 -0.076438 -0.046936 +-1.000000 -0.000003 -0.000000 +-0.995969 -0.076438 -0.046936 +-1.000000 -0.000003 -0.000000 +-0.995013 -0.099747 0.000000 +-1.000000 -0.000003 -0.000000 +-0.995969 -0.076438 0.046936 +-0.995013 -0.099747 0.000000 +-0.995969 -0.076438 0.046936 +-1.000000 -0.000003 -0.000000 +-1.000000 -0.000003 -0.000000 +-0.995969 -0.076438 0.046936 +-1.000000 -0.000001 -0.000000 +-0.995568 -0.014660 0.092898 +-1.000000 -0.000001 -0.000000 +-0.995969 -0.076438 0.046936 +-1.000000 -0.000003 -0.000000 +-1.000000 0.000001 -0.000000 +-0.995568 0.014660 0.092899 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-0.995568 0.014660 0.092899 +-0.995568 -0.014660 0.092898 +-1.000000 0.000001 -0.000000 +-0.995969 0.076438 0.046936 +-0.995568 0.014660 0.092899 +-0.995969 0.076438 0.046936 +-1.000000 0.000001 -0.000000 +-1.000000 0.000003 -0.000000 +-0.995969 0.076438 0.046936 +-1.000000 0.000003 -0.000000 +-0.995013 0.099747 -0.000000 +-1.000000 0.000003 -0.000000 +-0.995969 0.076438 0.046936 +-1.000000 0.000003 -0.000000 +-1.000000 0.000003 -0.000000 +-0.995969 0.076438 -0.046936 +-1.000000 0.000003 -0.000000 +-1.000000 0.000003 -0.000000 +-0.995969 0.076438 -0.046936 +-0.995013 0.099747 -0.000000 +-0.995969 0.076438 -0.046936 +-0.995568 0.014660 -0.092899 +-0.956045 0.148069 -0.253090 +-0.956045 -0.148068 -0.253090 +-0.956045 0.148069 -0.253090 +-0.995568 0.014660 -0.092899 +-0.956045 -0.148068 -0.253090 +-0.995568 0.014660 -0.092899 +-0.995568 -0.014660 -0.092898 +-0.995568 -0.014660 -0.092898 +-0.995969 -0.076438 -0.046936 +-0.956045 -0.148068 -0.253090 +-0.946007 -0.324145 0.000000 +-0.995969 -0.076438 -0.046936 +-0.995013 -0.099747 0.000000 +-0.995969 -0.076438 -0.046936 +-0.946007 -0.324145 0.000000 +-0.956045 -0.148068 -0.253090 +-0.946007 -0.324145 0.000000 +-0.995969 -0.076438 0.046936 +-0.956045 -0.148068 0.253089 +-0.995969 -0.076438 0.046936 +-0.946007 -0.324145 0.000000 +-0.995013 -0.099747 0.000000 +-0.995969 -0.076438 0.046936 +-0.995568 -0.014660 0.092898 +-0.956045 -0.148068 0.253089 +-0.956045 0.148067 0.253088 +-0.995568 -0.014660 0.092898 +-0.995568 0.014660 0.092899 +-0.995568 -0.014660 0.092898 +-0.956045 0.148067 0.253088 +-0.956045 -0.148068 0.253089 +-0.995568 0.014660 0.092899 +-0.995969 0.076438 0.046936 +-0.956045 0.148067 0.253088 +-0.946007 0.324145 -0.000000 +-0.956045 0.148067 0.253088 +-0.995969 0.076438 0.046936 +-0.995969 0.076438 0.046936 +-0.995013 0.099747 -0.000000 +-0.946007 0.324145 -0.000000 +-0.995969 0.076438 -0.046936 +-0.946007 0.324145 -0.000000 +-0.995013 0.099747 -0.000000 +-0.946007 0.324145 -0.000000 +-0.995969 0.076438 -0.046936 +-0.956045 0.148069 -0.253090 +-0.946007 -0.324145 0.000000 +-0.946007 0.324145 -0.000000 +-0.956045 0.148069 -0.253090 +-0.946007 -0.324145 0.000000 +-0.956045 0.148069 -0.253090 +-0.956045 -0.148068 -0.253090 +-0.257295 0.781779 0.567997 +0.000000 0.809016 0.587786 +-0.000000 0.309017 0.951057 +-0.257295 0.781779 0.567997 +-0.000000 0.309017 0.951057 +-0.257294 0.298614 0.919037 +-0.000000 0.309017 0.951057 +-0.000000 -0.309017 0.951057 +-0.257294 0.298614 0.919037 +-0.257294 0.298614 0.919037 +-0.000000 -0.309017 0.951057 +-0.257294 -0.298614 0.919037 +-0.257294 -0.298614 0.919037 +-0.000000 -0.309017 0.951057 +-0.000000 -0.809016 0.587786 +-0.257294 -0.298614 0.919037 +-0.000000 -0.809016 0.587786 +-0.257295 -0.781780 0.567997 +-0.000000 -0.809016 0.587786 +-0.000000 -1.000000 0.000000 +-0.257295 -0.781780 0.567997 +-0.257295 -0.781780 0.567997 +-0.000000 -1.000000 0.000000 +-0.257295 -0.966333 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.809016 -0.587786 +-0.257295 -0.966333 -0.000000 +-0.257295 -0.966333 -0.000000 +-0.000000 -0.809016 -0.587786 +-0.257295 -0.781780 -0.567996 +-0.257295 -0.781780 -0.567996 +-0.000000 -0.809016 -0.587786 +0.000000 -0.309017 -0.951057 +-0.257295 -0.781780 -0.567996 +0.000000 -0.309017 -0.951057 +-0.257294 -0.298614 -0.919037 +0.000000 -0.309017 -0.951057 +0.000000 0.309017 -0.951057 +-0.257294 -0.298614 -0.919037 +-0.257294 -0.298614 -0.919037 +0.000000 0.309017 -0.951057 +-0.257294 0.298613 -0.919037 +-0.257294 0.298613 -0.919037 +0.000000 0.309017 -0.951057 +0.000000 0.809016 -0.587786 +-0.257294 0.298613 -0.919037 +0.000000 0.809016 -0.587786 +-0.257295 0.781779 -0.567998 +0.000000 1.000000 0.000000 +-0.257295 0.966333 0.000000 +-0.257295 0.781779 -0.567998 +0.000000 1.000000 0.000000 +-0.257295 0.781779 -0.567998 +0.000000 0.809016 -0.587786 +0.000000 0.809016 0.587786 +-0.257295 0.781779 0.567997 +-0.257295 0.966333 0.000000 +0.000000 0.809016 0.587786 +-0.257295 0.966333 0.000000 +0.000000 1.000000 0.000000 +-0.956045 -0.148068 -0.253089 +-0.946008 0.324143 0.000000 +-0.956045 0.148067 -0.253089 +-0.946008 -0.324143 -0.000000 +-0.946008 0.324143 0.000000 +-0.956045 -0.148068 -0.253089 +-0.044018 0.808231 -0.587217 +-0.044018 0.808231 -0.587217 +-0.044018 0.308718 -0.950135 +-0.044018 0.808231 -0.587217 +-0.044018 0.308718 -0.950135 +-0.044018 0.308718 -0.950135 +-0.044018 0.808231 -0.587217 +-0.044018 0.999031 0.000000 +-0.044018 0.808231 -0.587217 +-0.044018 0.999031 0.000000 +-0.044018 0.808231 -0.587217 +-0.044018 0.999031 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.044018 0.808231 0.587217 +-0.044018 0.999031 0.000000 +-0.044018 0.999031 0.000000 +-0.044018 0.999031 0.000000 +-0.044018 0.808231 0.587217 +-0.044018 0.808231 0.587217 +-0.044018 -0.308718 -0.950135 +-0.044018 -0.808231 -0.587217 +-0.044018 -0.308718 -0.950135 +-0.044018 -0.808231 -0.587217 +-0.044018 -0.308718 -0.950135 +-0.044018 -0.808231 -0.587217 +-0.044018 0.308718 0.950135 +-0.044018 0.808231 0.587217 +-0.044018 0.308718 0.950135 +-0.044018 0.808231 0.587217 +-0.044018 0.308718 0.950135 +-0.044018 0.808231 0.587217 +-0.044018 -0.808231 -0.587217 +-0.044018 -0.808231 -0.587217 +-0.044019 -0.999031 -0.000000 +-0.044018 -0.808231 -0.587217 +-0.044019 -0.999031 -0.000000 +-0.044019 -0.999031 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.044019 -0.999031 -0.000000 +-0.044018 -0.808231 0.587217 +-0.044019 -0.999031 -0.000000 +-0.044018 -0.808231 0.587217 +-0.044019 -0.999031 -0.000000 +-0.044018 -0.808231 0.587217 +-0.044018 -0.808231 0.587217 +-0.044018 -0.808231 0.587217 +-0.044018 -0.308718 0.950135 +-0.044018 -0.808231 0.587217 +-0.044018 -0.308718 0.950135 +-0.044018 -0.308718 0.950135 +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 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.044018 0.308718 -0.950135 +-0.044018 -0.308718 -0.950135 +-0.044018 0.308718 -0.950135 +-0.044018 -0.308718 -0.950135 +-0.044018 0.308718 -0.950135 +-0.044018 -0.308718 -0.950135 +-0.044018 -0.308718 0.950135 +-0.044018 0.308718 0.950135 +-0.044018 -0.308718 0.950135 +-0.044018 0.308718 0.950135 +-0.044018 -0.308718 0.950135 +-0.044018 0.308718 0.950135 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 -0.000001 -0.000000 +-0.257295 0.781779 0.567997 +-0.658954 0.232439 0.715369 +-0.658955 0.608528 0.442122 +-0.658954 0.232439 0.715369 +-0.257295 0.781779 0.567997 +-0.257294 0.298614 0.919037 +-0.658955 0.608528 0.442122 +-0.658957 0.752181 0.000000 +-0.257295 0.781779 0.567997 +-0.257295 0.781779 0.567997 +-0.658957 0.752181 0.000000 +-0.257295 0.966333 0.000000 +-0.658957 0.752181 0.000000 +-0.257295 0.781779 -0.567998 +-0.257295 0.966333 0.000000 +-0.257295 0.781779 -0.567998 +-0.658957 0.752181 0.000000 +-0.658956 0.608527 -0.442123 +-0.658954 0.232438 -0.715368 +-0.257295 0.781779 -0.567998 +-0.658956 0.608527 -0.442123 +-0.257294 0.298613 -0.919037 +-0.257295 0.781779 -0.567998 +-0.658954 0.232438 -0.715368 +-0.257294 -0.298614 -0.919037 +-0.257294 0.298613 -0.919037 +-0.658956 -0.232439 -0.715366 +-0.658956 -0.232439 -0.715366 +-0.257294 0.298613 -0.919037 +-0.658954 0.232438 -0.715368 +-0.658956 -0.232439 -0.715366 +-0.257295 -0.781780 -0.567996 +-0.257294 -0.298614 -0.919037 +-0.257295 -0.781780 -0.567996 +-0.658956 -0.232439 -0.715366 +-0.658956 -0.608529 -0.442119 +-0.658957 -0.752181 -0.000000 +-0.257295 -0.781780 -0.567996 +-0.658956 -0.608529 -0.442119 +-0.658957 -0.752181 -0.000000 +-0.257295 -0.966333 -0.000000 +-0.257295 -0.781780 -0.567996 +-0.257295 -0.781780 0.567997 +-0.658957 -0.752181 -0.000000 +-0.658956 -0.608528 0.442120 +-0.658957 -0.752181 -0.000000 +-0.257295 -0.781780 0.567997 +-0.257295 -0.966333 -0.000000 +-0.658956 -0.608528 0.442120 +-0.658956 -0.232439 0.715367 +-0.257295 -0.781780 0.567997 +-0.257295 -0.781780 0.567997 +-0.658956 -0.232439 0.715367 +-0.257294 -0.298614 0.919037 +-0.257294 0.298614 0.919037 +-0.257294 -0.298614 0.919037 +-0.658954 0.232439 0.715369 +-0.658954 0.232439 0.715369 +-0.257294 -0.298614 0.919037 +-0.658956 -0.232439 0.715367 +-1.000000 0.000000 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000002 -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.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000002 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000002 -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.000001 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-0.995969 0.076439 0.046936 +-1.000000 0.000001 -0.000000 +-1.000000 0.000004 -0.000000 +-1.000000 0.000001 -0.000000 +-0.995969 0.076439 0.046936 +-0.995568 0.014660 0.092899 +-1.000000 -0.000003 -0.000000 +-1.000000 0.000001 -0.000000 +-0.995568 -0.014661 0.092898 +-1.000000 0.000001 -0.000000 +-0.995568 0.014660 0.092899 +-0.995568 -0.014661 0.092898 +-1.000000 -0.000003 -0.000000 +-0.995969 -0.076440 0.046936 +-1.000000 -0.000005 -0.000000 +-0.995969 -0.076440 0.046936 +-1.000000 -0.000003 -0.000000 +-0.995568 -0.014661 0.092898 +-0.995969 -0.076440 0.046936 +-1.000000 -0.000005 -0.000000 +-1.000000 -0.000005 -0.000000 +-1.000000 -0.000005 -0.000000 +-0.995969 -0.076440 0.046936 +-0.995013 -0.099749 -0.000000 +-0.995969 -0.076439 -0.046936 +-1.000000 -0.000005 -0.000000 +-0.995013 -0.099749 -0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000005 -0.000000 +-0.995969 -0.076439 -0.046936 +-1.000000 -0.000001 -0.000000 +-0.995969 -0.076439 -0.046936 +-0.995568 -0.014660 -0.092898 +-0.995969 -0.076439 -0.046936 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000001 -0.000000 +-0.995568 0.014661 -0.092899 +-1.000000 0.000003 -0.000000 +-0.995568 0.014661 -0.092899 +-1.000000 -0.000001 -0.000000 +-0.995568 -0.014660 -0.092898 +-0.995969 0.076440 -0.046936 +-1.000000 0.000003 -0.000000 +-0.995568 0.014661 -0.092899 +-1.000000 0.000005 -0.000000 +-1.000000 0.000003 -0.000000 +-0.995969 0.076440 -0.046936 +-1.000000 0.000005 -0.000000 +-0.995969 0.076440 -0.046936 +-0.995013 0.099749 0.000000 +-0.995969 0.076440 -0.046936 +-1.000000 0.000005 -0.000000 +-1.000000 0.000005 -0.000000 +-1.000000 0.000005 -0.000000 +-0.995969 0.076439 0.046936 +-1.000000 0.000004 -0.000000 +-0.995969 0.076439 0.046936 +-1.000000 0.000005 -0.000000 +-0.995013 0.099749 0.000000 +-0.995969 0.076439 0.046936 +-0.956045 0.148067 0.253088 +-0.995568 0.014660 0.092899 +-0.995568 -0.014661 0.092898 +-0.995568 0.014660 0.092899 +-0.956045 -0.148067 0.253089 +-0.995568 0.014660 0.092899 +-0.956045 0.148067 0.253088 +-0.956045 -0.148067 0.253089 +-0.995568 -0.014661 0.092898 +-0.956045 -0.148067 0.253089 +-0.995969 -0.076440 0.046936 +-0.946008 -0.324143 -0.000000 +-0.995969 -0.076440 0.046936 +-0.956045 -0.148067 0.253089 +-0.995969 -0.076440 0.046936 +-0.946008 -0.324143 -0.000000 +-0.995013 -0.099749 -0.000000 +-0.946008 -0.324143 -0.000000 +-0.995969 -0.076439 -0.046936 +-0.995013 -0.099749 -0.000000 +-0.995969 -0.076439 -0.046936 +-0.946008 -0.324143 -0.000000 +-0.956045 -0.148068 -0.253089 +-0.995969 -0.076439 -0.046936 +-0.956045 -0.148068 -0.253089 +-0.995568 -0.014660 -0.092898 +-0.956045 0.148067 -0.253089 +-0.995568 -0.014660 -0.092898 +-0.956045 -0.148068 -0.253089 +-0.995568 -0.014660 -0.092898 +-0.956045 0.148067 -0.253089 +-0.995568 0.014661 -0.092899 +-0.995568 0.014661 -0.092899 +-0.956045 0.148067 -0.253089 +-0.995969 0.076440 -0.046936 +-0.995013 0.099749 0.000000 +-0.995969 0.076440 -0.046936 +-0.946008 0.324143 0.000000 +-0.995969 0.076440 -0.046936 +-0.956045 0.148067 -0.253089 +-0.946008 0.324143 0.000000 +-0.995969 0.076439 0.046936 +-0.946008 0.324143 0.000000 +-0.956045 0.148067 0.253088 +-0.946008 0.324143 0.000000 +-0.995969 0.076439 0.046936 +-0.995013 0.099749 0.000000 +-0.946008 0.324143 0.000000 +-0.946008 -0.324143 -0.000000 +-0.956045 0.148067 0.253088 +-0.956045 0.148067 0.253088 +-0.946008 -0.324143 -0.000000 +-0.956045 -0.148067 0.253089 +0.000000 0.309017 -0.951057 +0.257294 0.298614 -0.919037 +0.257294 0.781779 -0.567998 +0.000000 0.309017 -0.951057 +0.257294 0.781779 -0.567998 +0.000000 0.809016 -0.587786 +0.000000 -0.309017 -0.951057 +0.257294 -0.298614 -0.919037 +0.257294 0.298614 -0.919037 +0.000000 -0.309017 -0.951057 +0.257294 0.298614 -0.919037 +0.000000 0.309017 -0.951057 +-0.000000 -0.809016 -0.587786 +0.257294 -0.781780 -0.567997 +0.257294 -0.298614 -0.919037 +-0.000000 -0.809016 -0.587786 +0.257294 -0.298614 -0.919037 +0.000000 -0.309017 -0.951057 +-0.000000 -1.000000 0.000000 +0.257294 -0.966333 0.000000 +0.257294 -0.781780 -0.567997 +-0.000000 -1.000000 0.000000 +0.257294 -0.781780 -0.567997 +-0.000000 -0.809016 -0.587786 +-0.000000 -0.809016 0.587786 +0.257294 -0.781780 0.567997 +0.257294 -0.966333 0.000000 +-0.000000 -0.809016 0.587786 +0.257294 -0.966333 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -0.309017 0.951057 +0.257294 -0.298614 0.919037 +0.257294 -0.781780 0.567997 +-0.000000 -0.309017 0.951057 +0.257294 -0.781780 0.567997 +-0.000000 -0.809016 0.587786 +-0.000000 0.309017 0.951057 +0.257294 0.298614 0.919038 +0.257294 -0.298614 0.919037 +-0.000000 0.309017 0.951057 +0.257294 -0.298614 0.919037 +-0.000000 -0.309017 0.951057 +0.000000 0.809016 0.587786 +0.257294 0.781779 0.567998 +0.257294 0.298614 0.919038 +0.000000 0.809016 0.587786 +0.257294 0.298614 0.919038 +-0.000000 0.309017 0.951057 +0.000000 0.809016 0.587786 +0.000000 1.000000 0.000000 +0.257294 0.781779 0.567998 +0.257294 0.781779 0.567998 +0.000000 1.000000 0.000000 +0.257294 0.966333 -0.000000 +0.000000 1.000000 0.000000 +0.000000 0.809016 -0.587786 +0.257294 0.966333 -0.000000 +0.257294 0.966333 -0.000000 +0.000000 0.809016 -0.587786 +0.257294 0.781779 -0.567998 +0.946008 0.324143 -0.000000 +0.956045 -0.148067 0.253089 +0.946008 -0.324144 0.000000 +0.956045 -0.148067 0.253089 +0.946008 0.324143 -0.000000 +0.956045 0.148067 0.253089 +0.044018 0.308718 0.950135 +0.044018 0.308718 0.950135 +0.044018 0.808231 0.587217 +0.044018 0.308718 0.950135 +0.044018 0.808231 0.587217 +0.044018 0.808231 0.587217 +0.044019 0.999031 -0.000000 +0.044018 0.808231 0.587217 +0.044019 0.999031 -0.000000 +0.044018 0.808231 0.587217 +0.044019 0.999031 -0.000000 +0.044018 0.808231 0.587217 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.044018 0.808231 -0.587217 +0.044018 0.808231 -0.587217 +0.044019 0.999031 -0.000000 +0.044018 0.808231 -0.587217 +0.044019 0.999031 -0.000000 +0.044019 0.999031 -0.000000 +0.044018 -0.808231 0.587217 +0.044018 -0.308718 0.950135 +0.044018 -0.808231 0.587217 +0.044018 -0.308718 0.950135 +0.044018 -0.808231 0.587217 +0.044018 -0.308718 0.950135 +0.044018 0.808231 -0.587217 +0.044017 0.308718 -0.950135 +0.044018 0.808231 -0.587217 +0.044017 0.308718 -0.950135 +0.044018 0.808231 -0.587217 +0.044017 0.308718 -0.950135 +0.044018 -0.808231 0.587217 +0.044018 -0.999031 0.000000 +0.044018 -0.999031 0.000000 +0.044018 -0.999031 0.000000 +0.044018 -0.808231 0.587217 +0.044018 -0.808231 0.587217 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.044018 -0.808231 -0.587217 +0.044018 -0.999031 0.000000 +0.044018 -0.808231 -0.587217 +0.044018 -0.999031 0.000000 +0.044018 -0.808231 -0.587217 +0.044018 -0.999031 0.000000 +0.044017 -0.308718 -0.950135 +0.044017 -0.308718 -0.950135 +0.044018 -0.808231 -0.587217 +0.044017 -0.308718 -0.950135 +0.044018 -0.808231 -0.587217 +0.044018 -0.808231 -0.587217 +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 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.044018 -0.308718 0.950135 +0.044018 -0.308718 0.950135 +0.044018 0.308718 0.950135 +0.044018 -0.308718 0.950135 +0.044018 0.308718 0.950135 +0.044018 0.308718 0.950135 +0.044017 0.308718 -0.950135 +0.044017 0.308718 -0.950135 +0.044017 -0.308718 -0.950135 +0.044017 0.308718 -0.950135 +0.044017 -0.308718 -0.950135 +0.044017 -0.308718 -0.950135 +1.000000 0.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000002 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000002 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000001 0.000000 +0.658954 0.232439 -0.715369 +0.257294 0.781779 -0.567998 +0.257294 0.298614 -0.919037 +0.257294 0.781779 -0.567998 +0.658954 0.232439 -0.715369 +0.658954 0.608528 -0.442123 +0.658957 0.752181 -0.000000 +0.257294 0.781779 -0.567998 +0.658954 0.608528 -0.442123 +0.658957 0.752181 -0.000000 +0.257294 0.966333 -0.000000 +0.257294 0.781779 -0.567998 +0.257294 0.781779 0.567998 +0.658957 0.752181 -0.000000 +0.658955 0.608528 0.442123 +0.658957 0.752181 -0.000000 +0.257294 0.781779 0.567998 +0.257294 0.966333 -0.000000 +0.658955 0.608528 0.442123 +0.658954 0.232438 0.715369 +0.257294 0.781779 0.567998 +0.257294 0.781779 0.567998 +0.658954 0.232438 0.715369 +0.257294 0.298614 0.919038 +0.658954 0.232438 0.715369 +0.658956 -0.232440 0.715367 +0.257294 0.298614 0.919038 +0.257294 0.298614 0.919038 +0.658956 -0.232440 0.715367 +0.257294 -0.298614 0.919037 +0.257294 -0.781780 0.567997 +0.658956 -0.232440 0.715367 +0.658955 -0.608530 0.442120 +0.658956 -0.232440 0.715367 +0.257294 -0.781780 0.567997 +0.257294 -0.298614 0.919037 +0.658955 -0.608530 0.442120 +0.658956 -0.752181 0.000000 +0.257294 -0.781780 0.567997 +0.257294 -0.781780 0.567997 +0.658956 -0.752181 0.000000 +0.257294 -0.966333 0.000000 +0.658956 -0.752181 0.000000 +0.257294 -0.781780 -0.567997 +0.257294 -0.966333 0.000000 +0.257294 -0.781780 -0.567997 +0.658956 -0.752181 0.000000 +0.658956 -0.608529 -0.442120 +0.658956 -0.232438 -0.715367 +0.257294 -0.781780 -0.567997 +0.658956 -0.608529 -0.442120 +0.257294 -0.298614 -0.919037 +0.257294 -0.781780 -0.567997 +0.658956 -0.232438 -0.715367 +0.658956 -0.232438 -0.715367 +0.658954 0.232439 -0.715369 +0.257294 -0.298614 -0.919037 +0.257294 -0.298614 -0.919037 +0.658954 0.232439 -0.715369 +0.257294 0.298614 -0.919037 +1.000000 0.000000 0.000000 +1.000000 0.000002 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000002 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000002 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.000001 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000002 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000002 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000002 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.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000001 0.000000 +0.995969 0.076439 -0.046936 +0.995568 0.014660 -0.092899 +0.995969 0.076439 -0.046936 +1.000000 0.000001 0.000000 +1.000000 0.000004 0.000000 +1.000000 0.000001 0.000000 +0.995568 -0.014661 -0.092898 +1.000000 -0.000003 0.000000 +0.995568 -0.014661 -0.092898 +1.000000 0.000001 0.000000 +0.995568 0.014660 -0.092899 +0.995969 -0.076440 -0.046936 +1.000000 -0.000003 0.000000 +0.995568 -0.014661 -0.092898 +1.000000 -0.000005 0.000000 +1.000000 -0.000003 0.000000 +0.995969 -0.076440 -0.046936 +1.000000 -0.000005 0.000000 +0.995969 -0.076440 -0.046936 +0.995013 -0.099749 0.000000 +0.995969 -0.076440 -0.046936 +1.000000 -0.000005 0.000000 +1.000000 -0.000005 0.000000 +1.000000 -0.000005 0.000000 +0.995969 -0.076439 0.046936 +1.000000 -0.000004 0.000000 +0.995969 -0.076439 0.046936 +1.000000 -0.000005 0.000000 +0.995013 -0.099749 0.000000 +0.995969 -0.076439 0.046936 +1.000000 -0.000001 0.000000 +1.000000 -0.000004 0.000000 +1.000000 -0.000001 0.000000 +0.995969 -0.076439 0.046936 +0.995568 -0.014660 0.092898 +1.000000 0.000003 0.000000 +1.000000 -0.000001 0.000000 +0.995568 0.014661 0.092899 +1.000000 -0.000001 0.000000 +0.995568 -0.014660 0.092898 +0.995568 0.014661 0.092899 +1.000000 0.000003 0.000000 +0.995969 0.076440 0.046936 +1.000000 0.000005 0.000000 +0.995969 0.076440 0.046936 +1.000000 0.000003 0.000000 +0.995568 0.014661 0.092899 +0.995969 0.076440 0.046936 +1.000000 0.000005 0.000000 +1.000000 0.000005 0.000000 +1.000000 0.000005 0.000000 +0.995969 0.076440 0.046936 +0.995013 0.099749 -0.000000 +0.995969 0.076439 -0.046936 +1.000000 0.000005 0.000000 +0.995013 0.099749 -0.000000 +1.000000 0.000004 0.000000 +1.000000 0.000005 0.000000 +0.995969 0.076439 -0.046936 +0.995969 0.076439 -0.046936 +0.956045 0.148068 -0.253090 +0.995568 0.014660 -0.092899 +0.956044 -0.148068 -0.253090 +0.995568 0.014660 -0.092899 +0.956045 0.148068 -0.253090 +0.995568 0.014660 -0.092899 +0.956044 -0.148068 -0.253090 +0.995568 -0.014661 -0.092898 +0.995568 -0.014661 -0.092898 +0.956044 -0.148068 -0.253090 +0.995969 -0.076440 -0.046936 +0.995013 -0.099749 0.000000 +0.995969 -0.076440 -0.046936 +0.946008 -0.324144 0.000000 +0.995969 -0.076440 -0.046936 +0.956044 -0.148068 -0.253090 +0.946008 -0.324144 0.000000 +0.995969 -0.076439 0.046936 +0.946008 -0.324144 0.000000 +0.956045 -0.148067 0.253089 +0.946008 -0.324144 0.000000 +0.995969 -0.076439 0.046936 +0.995013 -0.099749 0.000000 +0.995969 -0.076439 0.046936 +0.956045 -0.148067 0.253089 +0.995568 -0.014660 0.092898 +0.995568 0.014661 0.092899 +0.995568 -0.014660 0.092898 +0.956045 0.148067 0.253089 +0.995568 -0.014660 0.092898 +0.956045 -0.148067 0.253089 +0.956045 0.148067 0.253089 +0.995568 0.014661 0.092899 +0.956045 0.148067 0.253089 +0.995969 0.076440 0.046936 +0.946008 0.324143 -0.000000 +0.995969 0.076440 0.046936 +0.956045 0.148067 0.253089 +0.995969 0.076440 0.046936 +0.946008 0.324143 -0.000000 +0.995013 0.099749 -0.000000 +0.946008 0.324143 -0.000000 +0.995969 0.076439 -0.046936 +0.995013 0.099749 -0.000000 +0.995969 0.076439 -0.046936 +0.946008 0.324143 -0.000000 +0.956045 0.148068 -0.253090 +0.946008 0.324143 -0.000000 +0.946008 -0.324144 0.000000 +0.956045 0.148068 -0.253090 +0.956045 0.148068 -0.253090 +0.946008 -0.324144 0.000000 +0.956044 -0.148068 -0.253090 +0.257294 0.298613 0.919037 +-0.000000 0.309017 0.951057 +0.257295 0.781779 0.567998 +0.000000 0.809016 0.587786 +0.257295 0.781779 0.567998 +-0.000000 0.309017 0.951057 +-0.000000 0.309017 0.951057 +0.257294 0.298613 0.919037 +-0.000000 -0.309017 0.951057 +0.257294 0.298613 0.919037 +0.257294 -0.298614 0.919037 +-0.000000 -0.309017 0.951057 +0.257295 -0.781780 0.567996 +-0.000000 -0.809016 0.587786 +0.257294 -0.298614 0.919037 +-0.000000 -0.309017 0.951057 +0.257294 -0.298614 0.919037 +-0.000000 -0.809016 0.587786 +-0.000000 -0.809016 0.587786 +0.257295 -0.781780 0.567996 +-0.000000 -1.000000 0.000000 +0.257295 -0.781780 0.567996 +0.257295 -0.966333 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.257295 -0.966333 -0.000000 +-0.000000 -0.809016 -0.587786 +0.257295 -0.966333 -0.000000 +0.257295 -0.781779 -0.567997 +-0.000000 -0.809016 -0.587786 +0.257295 -0.298614 -0.919037 +0.000000 -0.309017 -0.951057 +0.257295 -0.781779 -0.567997 +-0.000000 -0.809016 -0.587786 +0.257295 -0.781779 -0.567997 +0.000000 -0.309017 -0.951057 +0.000000 -0.309017 -0.951057 +0.257295 -0.298614 -0.919037 +0.000000 0.309017 -0.951057 +0.257295 -0.298614 -0.919037 +0.257294 0.298614 -0.919037 +0.000000 0.309017 -0.951057 +0.257295 0.781779 -0.567997 +0.000000 0.809016 -0.587786 +0.257294 0.298614 -0.919037 +0.000000 0.309017 -0.951057 +0.257294 0.298614 -0.919037 +0.000000 0.809016 -0.587786 +0.000000 1.000000 0.000000 +0.257295 0.781779 -0.567997 +0.257295 0.966333 0.000000 +0.257295 0.781779 -0.567997 +0.000000 1.000000 0.000000 +0.000000 0.809016 -0.587786 +0.000000 0.809016 0.587786 +0.257295 0.966333 0.000000 +0.257295 0.781779 0.567998 +0.257295 0.966333 0.000000 +0.000000 0.809016 0.587786 +0.000000 1.000000 0.000000 +0.956045 -0.148068 -0.253089 +0.946007 0.324145 0.000000 +0.946007 -0.324145 -0.000000 +0.946007 0.324145 0.000000 +0.956045 -0.148068 -0.253089 +0.956045 0.148067 -0.253089 +0.044018 0.808232 -0.587217 +0.044018 0.308718 -0.950135 +0.044018 0.808232 -0.587217 +0.044018 0.308718 -0.950135 +0.044018 0.808232 -0.587217 +0.044018 0.308718 -0.950134 +0.044018 0.808232 -0.587217 +0.044018 0.999031 0.000000 +0.044018 0.999031 0.000000 +0.044018 0.999031 0.000000 +0.044018 0.808232 -0.587217 +0.044018 0.808232 -0.587217 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.044018 0.808232 0.587217 +0.044018 0.808231 0.587217 +0.044018 0.999031 0.000000 +0.044018 0.999031 0.000000 +0.044018 0.999031 0.000000 +0.044018 0.808231 0.587217 +0.044018 -0.308718 -0.950135 +0.044018 -0.808231 -0.587217 +0.044018 -0.808232 -0.587217 +0.044018 -0.808231 -0.587217 +0.044018 -0.308718 -0.950135 +0.044018 -0.308718 -0.950135 +0.044018 0.308718 0.950135 +0.044018 0.808231 0.587217 +0.044018 0.808232 0.587217 +0.044018 0.808231 0.587217 +0.044018 0.308718 0.950135 +0.044018 0.308718 0.950135 +0.044018 -0.808231 -0.587217 +0.044019 -0.999031 -0.000000 +0.044018 -0.808232 -0.587217 +0.044019 -0.999031 -0.000000 +0.044018 -0.808231 -0.587217 +0.044019 -0.999031 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.044019 -0.999031 -0.000000 +0.044018 -0.808232 0.587217 +0.044018 -0.808232 0.587217 +0.044018 -0.808232 0.587217 +0.044019 -0.999031 -0.000000 +0.044019 -0.999031 -0.000000 +0.044018 -0.808232 0.587217 +0.044018 -0.308718 0.950135 +0.044018 -0.808232 0.587217 +0.044018 -0.308718 0.950135 +0.044018 -0.808232 0.587217 +0.044018 -0.308718 0.950134 +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 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.044018 0.308718 -0.950135 +0.044018 0.308718 -0.950134 +0.044018 -0.308718 -0.950135 +0.044018 0.308718 -0.950135 +0.044018 -0.308718 -0.950135 +0.044018 -0.308718 -0.950135 +0.044018 -0.308718 0.950135 +0.044018 -0.308718 0.950134 +0.044018 0.308718 0.950135 +0.044018 -0.308718 0.950135 +0.044018 0.308718 0.950135 +0.044018 0.308718 0.950135 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000002 0.000000 +0.257295 0.781779 0.567998 +0.658954 0.232438 0.715369 +0.257294 0.298613 0.919037 +0.658954 0.232438 0.715369 +0.257295 0.781779 0.567998 +0.658956 0.608527 0.442123 +0.658957 0.752180 0.000000 +0.658956 0.608527 0.442123 +0.257295 0.781779 0.567998 +0.257295 0.781779 0.567998 +0.257295 0.966333 0.000000 +0.658957 0.752180 0.000000 +0.658957 0.752180 0.000000 +0.257295 0.781779 -0.567997 +0.658955 0.608528 -0.442122 +0.257295 0.781779 -0.567997 +0.658957 0.752180 0.000000 +0.257295 0.966333 0.000000 +0.658954 0.232439 -0.715368 +0.658955 0.608528 -0.442122 +0.257295 0.781779 -0.567997 +0.658954 0.232439 -0.715368 +0.257295 0.781779 -0.567997 +0.257294 0.298614 -0.919037 +0.658956 -0.232438 -0.715366 +0.257294 0.298614 -0.919037 +0.257295 -0.298614 -0.919037 +0.257294 0.298614 -0.919037 +0.658956 -0.232438 -0.715366 +0.658954 0.232439 -0.715368 +0.658956 -0.232438 -0.715366 +0.257295 -0.781779 -0.567997 +0.658957 -0.608528 -0.442119 +0.257295 -0.781779 -0.567997 +0.658956 -0.232438 -0.715366 +0.257295 -0.298614 -0.919037 +0.658957 -0.752180 -0.000000 +0.257295 -0.781779 -0.567997 +0.257295 -0.966333 -0.000000 +0.658957 -0.752180 -0.000000 +0.658957 -0.608528 -0.442119 +0.257295 -0.781779 -0.567997 +0.257295 -0.781780 0.567996 +0.658957 -0.752180 -0.000000 +0.257295 -0.966333 -0.000000 +0.658957 -0.752180 -0.000000 +0.257295 -0.781780 0.567996 +0.658956 -0.608529 0.442119 +0.658956 -0.232440 0.715367 +0.658956 -0.608529 0.442119 +0.257295 -0.781780 0.567996 +0.257295 -0.781780 0.567996 +0.257294 -0.298614 0.919037 +0.658956 -0.232440 0.715367 +0.658954 0.232438 0.715369 +0.257294 -0.298614 0.919037 +0.257294 0.298613 0.919037 +0.257294 -0.298614 0.919037 +0.658954 0.232438 0.715369 +0.658956 -0.232440 0.715367 +1.000000 -0.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000001 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.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.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000002 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.000001 0.000000 +1.000000 -0.000002 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000001 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.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.995969 0.076438 0.046936 +1.000000 0.000001 0.000000 +0.995568 0.014660 0.092899 +1.000000 0.000001 0.000000 +0.995969 0.076438 0.046936 +1.000000 0.000003 0.000000 +1.000000 -0.000001 0.000000 +0.995568 -0.014660 0.092898 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +0.995568 -0.014660 0.092898 +0.995568 0.014660 0.092899 +1.000000 -0.000001 0.000000 +0.995969 -0.076438 0.046936 +0.995568 -0.014660 0.092898 +0.995969 -0.076438 0.046936 +1.000000 -0.000001 0.000000 +1.000000 -0.000003 0.000000 +0.995969 -0.076438 0.046936 +1.000000 -0.000003 0.000000 +0.995013 -0.099747 -0.000000 +1.000000 -0.000003 0.000000 +0.995969 -0.076438 0.046936 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.995969 -0.076438 -0.046936 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.995969 -0.076438 -0.046936 +0.995013 -0.099747 -0.000000 +1.000000 -0.000001 0.000000 +0.995969 -0.076438 -0.046936 +1.000000 -0.000003 0.000000 +0.995969 -0.076438 -0.046936 +1.000000 -0.000001 0.000000 +0.995568 -0.014660 -0.092898 +1.000000 -0.000001 0.000000 +1.000000 0.000001 0.000000 +0.995568 0.014660 -0.092899 +1.000000 -0.000001 0.000000 +0.995568 0.014660 -0.092899 +0.995568 -0.014660 -0.092898 +0.995568 0.014660 -0.092899 +1.000000 0.000001 0.000000 +0.995969 0.076438 -0.046936 +1.000000 0.000001 0.000000 +1.000000 0.000003 0.000000 +0.995969 0.076438 -0.046936 +1.000000 0.000003 0.000000 +0.995969 0.076438 -0.046936 +1.000000 0.000003 0.000000 +0.995969 0.076438 -0.046936 +1.000000 0.000003 0.000000 +0.995013 0.099747 0.000000 +1.000000 0.000003 0.000000 +0.995969 0.076438 0.046936 +0.995013 0.099747 0.000000 +0.995969 0.076438 0.046936 +1.000000 0.000003 0.000000 +1.000000 0.000003 0.000000 +0.995969 0.076438 0.046936 +0.995568 0.014660 0.092899 +0.956045 0.148068 0.253089 +0.995568 -0.014660 0.092898 +0.956045 -0.148067 0.253089 +0.995568 0.014660 0.092899 +0.995568 0.014660 0.092899 +0.956045 -0.148067 0.253089 +0.956045 0.148068 0.253089 +0.995568 -0.014660 0.092898 +0.995969 -0.076438 0.046936 +0.956045 -0.148067 0.253089 +0.946007 -0.324145 -0.000000 +0.956045 -0.148067 0.253089 +0.995969 -0.076438 0.046936 +0.995969 -0.076438 0.046936 +0.995013 -0.099747 -0.000000 +0.946007 -0.324145 -0.000000 +0.995969 -0.076438 -0.046936 +0.946007 -0.324145 -0.000000 +0.995013 -0.099747 -0.000000 +0.946007 -0.324145 -0.000000 +0.995969 -0.076438 -0.046936 +0.956045 -0.148068 -0.253089 +0.995969 -0.076438 -0.046936 +0.995568 -0.014660 -0.092898 +0.956045 -0.148068 -0.253089 +0.956045 0.148067 -0.253089 +0.956045 -0.148068 -0.253089 +0.995568 -0.014660 -0.092898 +0.956045 0.148067 -0.253089 +0.995568 -0.014660 -0.092898 +0.995568 0.014660 -0.092899 +0.995568 0.014660 -0.092899 +0.995969 0.076438 -0.046936 +0.956045 0.148067 -0.253089 +0.946007 0.324145 0.000000 +0.995969 0.076438 -0.046936 +0.995013 0.099747 0.000000 +0.995969 0.076438 -0.046936 +0.946007 0.324145 0.000000 +0.956045 0.148067 -0.253089 +0.946007 0.324145 0.000000 +0.995969 0.076438 0.046936 +0.956045 0.148068 0.253089 +0.995969 0.076438 0.046936 +0.946007 0.324145 0.000000 +0.995013 0.099747 0.000000 +0.956045 0.148068 0.253089 +0.956045 -0.148067 0.253089 +0.946007 -0.324145 -0.000000 +0.956045 0.148068 0.253089 +0.946007 -0.324145 -0.000000 +0.946007 0.324145 0.000000 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +0.000000 0.923880 0.382683 +0.000000 0.923880 0.382683 +0.000000 0.923880 0.382683 +0.000000 0.923880 0.382683 +0.000000 0.923880 0.382683 +0.000000 0.923880 0.382683 +0.000000 0.923880 -0.382683 +0.000000 0.923880 -0.382683 +0.000000 0.923880 -0.382683 +0.000000 0.923880 -0.382683 +0.000000 0.923880 -0.382683 +0.000000 0.923880 -0.382683 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +-0.000000 -0.923878 -0.382686 +-0.000000 -0.923878 -0.382686 +-0.000000 -0.923878 -0.382686 +-0.000000 -0.923878 -0.382686 +-0.000000 -0.923878 -0.382686 +-0.000000 -0.923878 -0.382686 +-0.000000 -0.923878 0.382686 +-0.000000 -0.923878 0.382686 +-0.000000 -0.923878 0.382686 +-0.000000 -0.923878 0.382686 +-0.000000 -0.923878 0.382686 +-0.000000 -0.923878 0.382686 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.000001 +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 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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.340896 0.000000 0.940101 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.340896 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.640952 0.000000 0.767581 +-0.340896 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.784613 -0.000000 0.619985 +-0.794472 0.000000 0.607301 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.794472 0.000000 0.607301 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.996690 -0.000000 0.081295 +-1.000000 0.000000 -0.000000 +-0.996690 -0.000000 0.081295 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.980078 0.000001 0.198613 +-0.996982 0.000000 0.077639 +-1.000000 0.000000 -0.000000 +-0.996982 0.000000 0.077639 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.805311 0.000000 0.592852 +-0.864225 0.000001 0.503106 +-0.864225 0.000000 0.503106 +-0.864225 0.000001 0.503106 +-0.805311 0.000000 0.592852 +-0.783838 0.000000 0.620965 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.805311 0.000000 0.592852 +-0.640952 0.000000 0.767581 +-0.783838 0.000000 0.620965 +-0.805311 0.000000 0.592852 +-0.640952 0.000000 0.767581 +-0.340896 0.000000 0.940101 +-0.640952 0.000000 0.767581 +-0.340896 0.000000 0.940101 +-0.640952 0.000000 0.767581 +-0.340896 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.021371 0.000000 0.999772 +-0.340896 0.000000 0.940101 +-0.021371 0.000000 0.999772 +-0.340896 0.000000 0.940101 +-0.021371 0.000000 0.999772 +-0.340895 0.000000 0.940101 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.340895 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.640952 0.000000 0.767581 +-0.340896 0.000000 0.940101 +-0.340895 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.784613 -0.000000 0.619985 +-0.640952 0.000000 0.767581 +-0.811979 -0.000000 0.583687 +-0.784613 -0.000000 0.619985 +-0.864225 -0.000002 0.503105 +-0.973040 -0.000001 0.230634 +-0.864227 -0.000001 0.503103 +-0.864227 -0.000001 0.503103 +-0.973040 -0.000001 0.230634 +-0.996690 -0.000000 0.081295 +-0.996690 -0.000000 0.081295 +-0.973040 -0.000001 0.230634 +-1.000000 0.000000 -0.000000 +-0.973040 -0.000001 0.230634 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.999780 0.000000 -0.020995 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.999780 0.000000 -0.020995 +-0.999780 0.000000 -0.020995 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.021371 0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.021371 0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.021371 0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.021371 0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -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.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.014703 0.000000 -0.999892 +0.000000 -0.000000 -1.000000 +-0.014703 0.000000 -0.999892 +0.000000 -0.000000 -1.000000 +-0.014703 0.000000 -0.999892 +0.000000 -0.000000 -1.000000 +0.000000 1.000000 0.000001 +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.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.000000 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 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.000000 -0.000000 -1.000000 +0.000000 -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.999780 0.000000 -0.020995 +-0.999780 0.000000 -0.020995 +-0.923879 0.000000 -0.382684 +-0.999780 0.000000 -0.020995 +-0.923879 0.000000 -0.382684 +-0.923879 0.000000 -0.382684 +-0.014703 0.000000 -0.999892 +-0.382683 0.000000 -0.923880 +-0.382683 0.000000 -0.923880 +-0.014703 0.000000 -0.999892 +-0.382683 0.000000 -0.923880 +-0.014703 0.000000 -0.999892 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000002 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000004 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000004 +-0.000000 -1.000000 0.000002 +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.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.996982 0.000000 0.077639 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503105 +-0.794472 0.000000 0.607301 +-0.783838 0.000000 0.620965 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.783838 0.000000 0.620965 +-0.640952 0.000000 0.767581 +-0.340896 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.640952 0.000000 0.767581 +-0.640952 0.000000 0.767581 +-0.340896 0.000000 0.940101 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +-0.340896 0.000000 0.940101 +-0.340896 0.000000 0.940101 +-0.021371 0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.021371 0.000000 0.999772 +-0.021371 0.000000 0.999772 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +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 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +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.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.864225 0.000000 0.503105 +-0.864227 -0.000001 0.503103 +-0.996690 -0.000000 0.081295 +-0.864225 0.000000 0.503105 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.864225 0.000000 0.503105 +-0.996690 -0.000000 0.081295 +-0.794472 0.000000 0.607301 +-0.784613 -0.000000 0.619985 +-0.864224 0.000000 0.503107 +-0.794472 0.000000 0.607301 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.996982 0.000000 0.077639 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.864225 0.000001 0.503106 +-0.783838 0.000000 0.620965 +-0.794472 0.000000 0.607301 +-0.864224 0.000000 0.503107 +-0.783838 0.000000 0.620965 +-0.864224 0.000000 0.503107 +-0.794472 0.000000 0.607301 +-0.864224 0.000000 0.503107 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.503106 -0.000000 0.864225 +0.503108 -0.000000 0.864223 +0.503108 -0.000000 0.864223 +0.503108 -0.000000 0.864223 +0.503106 -0.000000 0.864225 +0.503106 -0.000000 0.864225 +-0.503106 0.000000 -0.864225 +-0.503104 0.000000 -0.864226 +-0.503104 0.000000 -0.864226 +-0.503104 0.000000 -0.864226 +-0.503106 0.000000 -0.864225 +-0.503106 0.000000 -0.864225 +0.503104 -0.000000 0.864226 +0.503106 -0.000000 0.864225 +0.503106 -0.000000 0.864225 +0.503106 -0.000000 0.864225 +0.503104 -0.000000 0.864226 +0.503104 -0.000000 0.864226 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.503106 0.000000 -0.864225 +-0.503108 0.000000 -0.864223 +-0.503108 0.000000 -0.864223 +-0.503108 0.000000 -0.864223 +-0.503106 0.000000 -0.864225 +-0.503106 0.000000 -0.864225 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -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 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 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 +-1.000000 0.000003 -0.000000 +-1.000000 0.000003 -0.000000 +-1.000000 0.000003 -0.000000 +-1.000000 0.000003 -0.000000 +-1.000000 0.000003 -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.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +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 +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 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.340896 -0.000000 0.940101 +0.340896 -0.000000 0.940101 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +0.340896 -0.000000 0.940101 +0.640952 -0.000000 0.767581 +0.640952 -0.000000 0.767581 +0.340896 -0.000000 0.940101 +0.340896 -0.000000 0.940101 +0.340896 -0.000000 0.940101 +0.640952 -0.000000 0.767581 +0.640952 -0.000000 0.767581 +0.640952 -0.000000 0.767581 +0.794472 -0.000000 0.607301 +0.640952 -0.000000 0.767581 +0.794472 -0.000000 0.607301 +0.784313 0.000000 0.620365 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.996864 -0.000000 0.079136 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.996864 -0.000000 0.079136 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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.997191 0.000000 0.074901 +0.985440 0.000001 0.170022 +0.997191 0.000000 0.074901 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.864225 0.000002 0.503105 +0.997191 0.000000 0.074901 +0.864225 0.000001 0.503105 +0.997191 0.000000 0.074901 +0.864225 0.000002 0.503105 +0.985440 0.000001 0.170022 +0.640952 -0.000000 0.767581 +0.809877 0.000000 0.586599 +0.640952 -0.000000 0.767581 +0.640952 -0.000000 0.767581 +0.809877 0.000000 0.586599 +0.784351 0.000000 0.620318 +0.640952 -0.000000 0.767581 +0.340896 -0.000000 0.940101 +0.640952 -0.000000 0.767581 +0.340896 -0.000000 0.940101 +0.340896 -0.000000 0.940101 +0.640952 -0.000000 0.767581 +0.340896 -0.000000 0.940101 +0.021371 -0.000000 0.999772 +0.340896 -0.000000 0.940101 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +0.340896 -0.000000 0.940101 +0.340895 -0.000000 0.940101 +0.021371 -0.000000 0.999772 +0.340896 -0.000000 0.940101 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +0.340896 -0.000000 0.940101 +0.640952 -0.000000 0.767581 +0.340895 -0.000000 0.940101 +0.640952 -0.000000 0.767581 +0.340895 -0.000000 0.940101 +0.340896 -0.000000 0.940101 +0.640952 -0.000000 0.767581 +0.784313 0.000000 0.620365 +0.640952 -0.000000 0.767581 +0.640952 -0.000000 0.767581 +0.640952 -0.000000 0.767581 +0.784313 0.000000 0.620365 +0.809603 0.000000 0.586978 +0.784313 0.000000 0.620365 +0.864225 -0.000000 0.503105 +0.809603 0.000000 0.586978 +0.809603 0.000000 0.586978 +0.864225 -0.000000 0.503105 +0.864225 0.000002 0.503105 +0.996864 -0.000000 0.079136 +1.000000 -0.000000 0.000000 +0.977160 -0.000000 0.212506 +0.977160 -0.000000 0.212506 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.999780 -0.000000 -0.020995 +1.000000 -0.000000 0.000000 +0.999780 -0.000000 -0.020995 +1.000000 -0.000000 0.000000 +0.999780 -0.000000 -0.020995 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 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.021371 -0.000000 0.999772 +-0.000000 0.000000 1.000000 +0.021371 -0.000000 0.999772 +-0.000000 0.000000 1.000000 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.021371 -0.000000 0.999772 +-0.000000 0.000000 1.000000 +0.021371 -0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -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.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 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.014703 -0.000000 -0.999892 +0.000000 -0.000000 -1.000000 +0.014703 -0.000000 -0.999892 +0.000000 -0.000000 -1.000000 +0.014703 -0.000000 -0.999892 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +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.000000 +-0.000000 -1.000000 0.000001 +-0.000000 -1.000000 0.000002 +-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.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.000000 -0.000000 -1.000000 +0.000000 -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.999780 -0.000000 -0.020995 +0.923879 -0.000000 -0.382684 +0.999780 -0.000000 -0.020995 +0.999780 -0.000000 -0.020995 +0.923879 -0.000000 -0.382684 +0.923879 -0.000000 -0.382684 +0.014703 -0.000000 -0.999892 +0.382683 -0.000000 -0.923880 +0.382683 -0.000000 -0.923880 +0.382683 -0.000000 -0.923880 +0.014703 -0.000000 -0.999892 +0.014703 -0.000000 -0.999892 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000002 +0.000000 1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000004 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 -0.000004 +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.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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.997191 0.000000 0.074901 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.640952 -0.000000 0.767581 +0.640952 -0.000000 0.767581 +0.784351 0.000000 0.620318 +0.640952 -0.000000 0.767581 +0.784351 0.000000 0.620318 +0.794472 -0.000000 0.607301 +0.640952 -0.000000 0.767581 +0.640952 -0.000000 0.767581 +0.340896 -0.000000 0.940101 +0.340896 -0.000000 0.940101 +0.340896 -0.000000 0.940101 +0.640952 -0.000000 0.767581 +0.340896 -0.000000 0.940101 +0.340896 -0.000000 0.940101 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +0.340896 -0.000000 0.940101 +0.021371 -0.000000 0.999772 +0.021371 -0.000000 0.999772 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.021371 -0.000000 0.999772 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +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 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +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.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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.784313 0.000000 0.620365 +0.864224 -0.000000 0.503107 +0.864225 -0.000000 0.503105 +0.864224 -0.000000 0.503106 +0.864225 -0.000000 0.503105 +0.864224 -0.000000 0.503106 +0.864225 -0.000000 0.503105 +0.864224 -0.000000 0.503106 +0.996864 -0.000000 0.079136 +0.864224 -0.000000 0.503108 +0.864224 -0.000000 0.503107 +0.794472 -0.000000 0.607301 +0.784313 0.000000 0.620365 +0.794472 -0.000000 0.607301 +0.864224 -0.000000 0.503107 +0.864224 -0.000000 0.503107 +0.864224 -0.000000 0.503106 +0.864224 -0.000000 0.503106 +0.864224 -0.000000 0.503106 +0.864224 -0.000000 0.503107 +0.997191 0.000000 0.074901 +0.997191 0.000000 0.074901 +0.864224 -0.000000 0.503107 +0.864225 0.000001 0.503105 +0.864224 -0.000000 0.503107 +0.794472 -0.000000 0.607301 +0.784351 0.000000 0.620318 +0.794472 -0.000000 0.607301 +0.864224 -0.000000 0.503107 +0.864224 -0.000000 0.503108 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.503108 0.000000 0.864223 +-0.503106 0.000000 0.864225 +-0.503108 0.000000 0.864223 +-0.503106 0.000000 0.864225 +-0.503108 0.000000 0.864223 +-0.503106 0.000000 0.864225 +0.503106 -0.000000 -0.864225 +0.503104 -0.000000 -0.864226 +0.503106 -0.000000 -0.864225 +0.503106 -0.000000 -0.864225 +0.503104 -0.000000 -0.864226 +0.503104 -0.000000 -0.864226 +-0.503104 0.000000 0.864226 +-0.503106 0.000000 0.864225 +-0.503106 0.000000 0.864225 +-0.503106 0.000000 0.864225 +-0.503104 0.000000 0.864226 +-0.503104 0.000000 0.864226 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.503106 -0.000000 -0.864225 +0.503108 -0.000000 -0.864223 +0.503108 -0.000000 -0.864223 +0.503108 -0.000000 -0.864223 +0.503106 -0.000000 -0.864225 +0.503106 -0.000000 -0.864225 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -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 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 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 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 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.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +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.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000002 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000004 -0.000000 +-1.000000 0.000004 -0.000000 +-1.000000 0.000004 -0.000000 +-1.000000 0.000004 -0.000000 +-1.000000 0.000004 -0.000000 +-1.000000 0.000004 -0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.707106 0.653282 -0.270600 +-0.707106 0.653282 -0.270600 +-0.707106 0.653282 -0.270600 +-0.707106 0.653282 -0.270600 +-0.707106 0.653282 -0.270600 +-0.707106 0.653282 -0.270600 +-0.707105 0.270599 -0.653283 +-0.707105 0.270599 -0.653283 +-0.707105 0.270599 -0.653283 +-0.707105 0.270599 -0.653283 +-0.707105 0.270599 -0.653283 +-0.707105 0.270599 -0.653283 +-0.707106 -0.270598 -0.653282 +-0.707106 -0.270598 -0.653282 +-0.707106 -0.270598 -0.653282 +-0.707106 -0.270598 -0.653282 +-0.707106 -0.270598 -0.653282 +-0.707106 -0.270598 -0.653282 +-0.707102 -0.653287 -0.270598 +-0.707102 -0.653286 -0.270598 +-0.707102 -0.653286 -0.270598 +-0.707102 -0.653286 -0.270598 +-0.707102 -0.653287 -0.270598 +-0.707102 -0.653286 -0.270598 +-0.707105 -0.653284 0.270597 +-0.707105 -0.653284 0.270597 +-0.707105 -0.653284 0.270597 +-0.707105 -0.653284 0.270597 +-0.707105 -0.653284 0.270597 +-0.707105 -0.653284 0.270597 +-0.707103 -0.270599 0.653285 +-0.707103 -0.270599 0.653285 +-0.707103 -0.270599 0.653285 +-0.707103 -0.270599 0.653285 +-0.707103 -0.270599 0.653285 +-0.707103 -0.270599 0.653285 +-0.707105 0.270599 0.653283 +-0.707105 0.270599 0.653283 +-0.707105 0.270599 0.653283 +-0.707105 0.270599 0.653283 +-0.707105 0.270599 0.653283 +-0.707105 0.270599 0.653283 +-0.707104 0.653284 0.270599 +-0.707105 0.653284 0.270599 +-0.707105 0.653284 0.270599 +-0.707105 0.653284 0.270599 +-0.707104 0.653284 0.270599 +-0.707105 0.653284 0.270599 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000001 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000001 -0.000000 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +0.000000 -0.382683 -0.923880 +-0.000000 -0.923880 -0.382682 +-0.000000 -0.923880 -0.382682 +-0.000000 -0.923880 -0.382682 +-0.000000 -0.923880 -0.382682 +-0.000000 -0.923880 -0.382682 +-0.000000 -0.923880 -0.382682 +-0.000000 -0.923880 0.382683 +-0.000000 -0.923880 0.382683 +-0.000000 -0.923880 0.382683 +-0.000000 -0.923880 0.382683 +-0.000000 -0.923880 0.382683 +-0.000000 -0.923880 0.382683 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 -0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +-0.000000 0.382683 0.923880 +0.000000 0.923879 0.382685 +0.000000 0.923879 0.382685 +0.000000 0.923879 0.382685 +0.000000 0.923879 0.382685 +0.000000 0.923879 0.382685 +0.000000 0.923879 0.382685 +0.000000 0.923879 -0.382685 +0.000000 0.923879 -0.382685 +0.000000 0.923879 -0.382685 +0.000000 0.923879 -0.382685 +0.000000 0.923879 -0.382685 +0.000000 0.923879 -0.382685 +-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.000001 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.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 0.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.000001 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000001 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000001 +-1.000000 0.000000 -0.000001 +-1.000000 0.000001 -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.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.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.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 +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.000001 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000002 +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.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.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.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.000001 +-0.000000 -1.000000 -0.000001 +-0.000000 -1.000000 -0.000001 +-0.000000 -1.000000 -0.000001 +-0.000000 -1.000000 0.000001 +-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.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.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.000001 +-0.000000 -1.000000 -0.000001 +-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.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.890465 -0.404834 -0.207800 +-0.890466 -0.404833 0.207800 +-0.938189 0.272433 0.213501 +-0.938189 0.272433 0.213501 +-0.938189 0.272433 -0.213501 +-0.890465 -0.404834 -0.207800 +-0.416914 0.272433 0.867158 +-0.000000 -0.394952 0.918702 +-0.213788 0.277394 0.936668 +-0.000000 -0.394952 0.918702 +-0.416914 0.272433 0.867158 +-0.400736 -0.404833 0.821901 +-0.000000 -0.394954 -0.918701 +-0.400738 -0.404834 -0.821900 +-0.416917 0.272434 -0.867156 +-0.000000 -0.394954 -0.918701 +-0.416917 0.272434 -0.867156 +-0.213788 0.277397 -0.936667 +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.000001 +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.000001 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.881316 0.428931 -0.198242 +0.881133 0.428945 0.199022 +0.881316 0.428930 0.198243 +0.881133 0.428945 0.199022 +0.881316 0.428931 -0.198242 +0.881133 0.428946 -0.199021 +0.390104 0.428944 -0.814755 +0.202297 0.416579 -0.886306 +0.202297 0.416579 -0.886306 +0.202297 0.416579 -0.886306 +0.390104 0.428944 -0.814755 +0.389385 0.428930 -0.815107 +0.390103 0.428945 0.814755 +0.202295 0.416580 0.886306 +0.389384 0.428931 0.815107 +0.202295 0.416580 0.886306 +0.390103 0.428945 0.814755 +0.202295 0.416580 0.886306 +-0.902673 0.390139 0.181582 +-0.902674 0.390139 -0.181582 +-0.902674 0.390139 0.181580 +-0.902674 0.390139 -0.181582 +-0.902673 0.390139 0.181582 +-0.902673 0.390139 -0.181585 +-0.377893 0.390141 0.839635 +-0.205654 0.381909 0.901028 +-0.205654 0.381909 0.901028 +-0.205654 0.381909 0.901028 +-0.377893 0.390141 0.839635 +-0.377894 0.390141 0.839635 +-0.205654 0.381911 -0.901028 +-0.377892 0.390142 -0.839635 +-0.377892 0.390142 -0.839635 +-0.205654 0.381911 -0.901028 +-0.377892 0.390142 -0.839635 +-0.205654 0.381911 -0.901028 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000008 +0.000000 1.000000 -0.000008 +0.000000 1.000000 -0.000008 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000006 +0.981945 -0.000000 -0.189164 +0.981945 -0.000000 0.189165 +0.981945 -0.000000 -0.189164 +0.981945 -0.000000 0.189165 +0.981945 -0.000000 -0.189164 +0.981945 -0.000000 0.189165 +0.222515 -0.000000 -0.974929 +0.402924 -0.000000 -0.915233 +0.402924 -0.000000 -0.915233 +0.222515 -0.000000 -0.974929 +0.402924 -0.000000 -0.915233 +0.222515 -0.000000 -0.974929 +0.402927 -0.000000 0.915232 +0.222519 -0.000000 0.974928 +0.222519 -0.000000 0.974928 +0.222519 -0.000000 0.974928 +0.402927 -0.000000 0.915232 +0.402927 -0.000000 0.915232 +-0.698485 -0.449268 -0.557025 +-0.858674 0.255935 -0.444045 +-0.623988 0.255935 -0.738333 +-0.698486 -0.449267 0.557025 +-0.623985 0.255937 0.738336 +-0.858673 0.255935 0.444047 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000004 +-0.400738 -0.404834 -0.821900 +-0.623988 0.255935 -0.738333 +-0.416917 0.272434 -0.867156 +-0.623988 0.255935 -0.738333 +-0.400738 -0.404834 -0.821900 +-0.698485 -0.449268 -0.557025 +-0.890465 -0.404834 -0.207800 +-0.858674 0.255935 -0.444045 +-0.698485 -0.449268 -0.557025 +-0.858674 0.255935 -0.444045 +-0.890465 -0.404834 -0.207800 +-0.938189 0.272433 -0.213501 +-0.858673 0.255935 0.444047 +-0.890466 -0.404833 0.207800 +-0.698486 -0.449267 0.557025 +-0.890466 -0.404833 0.207800 +-0.858673 0.255935 0.444047 +-0.938189 0.272433 0.213501 +-0.623985 0.255937 0.738336 +-0.400736 -0.404833 0.821901 +-0.416914 0.272433 0.867158 +-0.400736 -0.404833 0.821901 +-0.623985 0.255937 0.738336 +-0.698486 -0.449267 0.557025 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000004 +0.000000 1.000000 0.000004 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000004 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.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.000003 +0.000000 1.000000 0.000003 +0.000000 1.000000 0.000003 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000003 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000003 +0.000000 1.000000 0.000003 +0.574885 0.422774 0.700549 +0.574885 0.422774 0.700549 +0.389384 0.428931 0.815107 +0.389384 0.428931 0.815107 +0.574885 0.422774 0.700549 +0.390103 0.428945 0.814755 +0.881316 0.428930 0.198243 +0.810908 0.422773 0.404587 +0.810908 0.422773 0.404587 +0.810908 0.422773 0.404587 +0.881316 0.428930 0.198243 +0.881133 0.428945 0.199022 +0.810908 0.422774 -0.404587 +0.881316 0.428931 -0.198242 +0.810908 0.422774 -0.404587 +0.881316 0.428931 -0.198242 +0.810908 0.422774 -0.404587 +0.881133 0.428946 -0.199021 +0.574885 0.422774 -0.700549 +0.389385 0.428930 -0.815107 +0.390104 0.428944 -0.814755 +0.389385 0.428930 -0.815107 +0.574885 0.422774 -0.700549 +0.574885 0.422774 -0.700549 +-0.576229 0.381911 -0.722568 +-0.576229 0.381911 -0.722568 +-0.377892 0.390142 -0.839635 +-0.377892 0.390142 -0.839635 +-0.576229 0.381911 -0.722568 +-0.377892 0.390142 -0.839635 +-0.902674 0.390139 -0.181582 +-0.902673 0.390139 -0.181585 +-0.832674 0.381907 -0.401000 +-0.902674 0.390139 -0.181582 +-0.832674 0.381907 -0.401000 +-0.832674 0.381907 -0.401000 +-0.832676 0.381908 0.400995 +-0.902674 0.390139 0.181580 +-0.832676 0.381908 0.400995 +-0.902674 0.390139 0.181580 +-0.832676 0.381908 0.400995 +-0.902673 0.390139 0.181582 +-0.377893 0.390141 0.839635 +-0.576232 0.381912 0.722565 +-0.377894 0.390141 0.839635 +-0.576232 0.381912 0.722565 +-0.576232 0.381912 0.722565 +-0.377894 0.390141 0.839635 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000006 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000002 +0.000000 1.000000 -0.000004 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000004 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000001 +0.000000 1.000000 -0.000001 +0.623493 -0.000000 0.781829 +0.623493 -0.000000 0.781829 +0.402927 -0.000000 0.915232 +0.402927 -0.000000 0.915232 +0.623493 -0.000000 0.781829 +0.402927 -0.000000 0.915232 +0.981945 -0.000000 0.189165 +0.900970 -0.000000 0.433882 +0.981945 -0.000000 0.189165 +0.900970 -0.000000 0.433882 +0.981945 -0.000000 0.189165 +0.900970 -0.000000 0.433882 +0.900968 -0.000000 -0.433886 +0.981945 -0.000000 -0.189164 +0.900968 -0.000000 -0.433886 +0.981945 -0.000000 -0.189164 +0.900968 -0.000000 -0.433886 +0.981945 -0.000000 -0.189164 +0.402924 -0.000000 -0.915233 +0.623493 -0.000000 -0.781829 +0.623493 -0.000000 -0.781829 +0.402924 -0.000000 -0.915233 +0.623493 -0.000000 -0.781829 +0.402924 -0.000000 -0.915233 +-0.277355 0.934960 -0.221189 +-0.277355 0.934960 -0.221189 +-0.277355 0.934960 -0.221189 +-0.277355 0.934960 -0.221189 +-0.277355 0.934960 -0.221189 +-0.277355 0.934960 -0.221189 +0.623490 0.000001 -0.781832 +0.623490 0.000001 -0.781832 +0.623490 0.000001 -0.781832 +0.623490 0.000001 -0.781832 +0.623490 0.000001 -0.781832 +0.623490 0.000001 -0.781832 +-0.623493 0.000002 0.781829 +-0.623493 0.000002 0.781829 +-0.623493 0.000002 0.781829 +-0.623493 0.000002 0.781829 +-0.623493 0.000002 0.781829 +-0.623493 0.000002 0.781829 +-0.277356 0.934959 0.221189 +-0.277356 0.934960 0.221189 +-0.277356 0.934959 0.221189 +-0.277356 0.934960 0.221189 +-0.277356 0.934960 0.221189 +-0.277356 0.934959 0.221189 +0.623501 -0.000000 0.781823 +0.623501 -0.000000 0.781823 +0.623501 -0.000000 0.781823 +0.623501 -0.000000 0.781823 +0.623501 -0.000000 0.781823 +0.623501 -0.000000 0.781823 +-0.623492 -0.000004 -0.781830 +-0.623492 -0.000004 -0.781830 +-0.623492 -0.000004 -0.781830 +-0.623492 -0.000004 -0.781830 +-0.623492 -0.000004 -0.781830 +-0.623492 -0.000004 -0.781830 +-0.623494 0.000000 0.781828 +-0.623494 0.000000 0.781828 +-0.623494 0.000000 0.781828 +-0.623494 0.000000 0.781828 +-0.623494 0.000000 0.781828 +-0.623494 0.000000 0.781828 +0.623491 -0.000000 -0.781831 +0.623491 -0.000000 -0.781831 +0.623491 -0.000000 -0.781831 +0.623491 -0.000000 -0.781831 +0.623491 -0.000000 -0.781831 +0.623491 -0.000000 -0.781831 +-0.105811 0.988708 -0.106115 +-0.105811 0.988708 -0.106115 +-0.105811 0.988708 -0.106115 +-0.105811 0.988708 -0.106115 +-0.105811 0.988708 -0.106115 +-0.105811 0.988708 -0.106115 +-0.623494 0.000000 -0.781828 +-0.623494 0.000000 -0.781828 +-0.623494 0.000000 -0.781828 +-0.623494 0.000000 -0.781828 +-0.623494 0.000000 -0.781828 +-0.623494 0.000000 -0.781828 +-0.105811 0.988708 0.106115 +-0.105811 0.988708 0.106115 +-0.105811 0.988708 0.106115 +-0.105811 0.988708 0.106115 +-0.105811 0.988708 0.106115 +-0.105811 0.988708 0.106115 +0.623491 -0.000000 0.781830 +0.623491 -0.000000 0.781830 +0.623491 -0.000000 0.781830 +0.623491 -0.000000 0.781830 +0.623491 -0.000000 0.781830 +0.623491 -0.000000 0.781830 +0.938188 0.272433 0.213502 +0.890465 -0.404834 -0.207800 +0.938188 0.272433 -0.213501 +0.890465 -0.404834 -0.207800 +0.938188 0.272433 0.213502 +0.890466 -0.404834 0.207799 +-0.000000 -0.394952 0.918702 +0.416915 0.272434 0.867157 +0.213788 0.277394 0.936668 +0.416915 0.272434 0.867157 +-0.000000 -0.394952 0.918702 +0.400736 -0.404833 0.821901 +-0.000000 -0.394954 -0.918701 +0.416918 0.272435 -0.867156 +0.400738 -0.404834 -0.821900 +0.416918 0.272435 -0.867156 +-0.000000 -0.394954 -0.918701 +0.213788 0.277397 -0.936667 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000002 +-0.881316 0.428931 -0.198242 +-0.881133 0.428945 0.199022 +-0.881133 0.428946 -0.199021 +-0.881133 0.428945 0.199022 +-0.881316 0.428931 -0.198242 +-0.881316 0.428930 0.198243 +-0.202297 0.416578 -0.886306 +-0.390103 0.428944 -0.814755 +-0.202297 0.416578 -0.886306 +-0.390103 0.428944 -0.814755 +-0.202297 0.416578 -0.886306 +-0.389384 0.428929 -0.815107 +-0.389384 0.428931 0.815107 +-0.202295 0.416579 0.886306 +-0.390102 0.428945 0.814755 +-0.202295 0.416579 0.886306 +-0.202295 0.416579 0.886306 +-0.390102 0.428945 0.814755 +0.902673 0.390140 0.181582 +0.902674 0.390139 -0.181578 +0.902673 0.390140 0.181584 +0.902673 0.390140 0.181584 +0.902674 0.390139 -0.181578 +0.902674 0.390139 -0.181581 +0.377892 0.390140 0.839636 +0.205654 0.381909 0.901028 +0.377892 0.390140 0.839636 +0.205654 0.381909 0.901028 +0.377892 0.390140 0.839636 +0.205654 0.381909 0.901028 +0.205654 0.381911 -0.901028 +0.377892 0.390141 -0.839635 +0.205654 0.381911 -0.901028 +0.377892 0.390141 -0.839635 +0.205654 0.381911 -0.901028 +0.377892 0.390141 -0.839635 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.981945 0.000000 -0.189165 +-0.981945 0.000000 0.189165 +-0.981945 0.000000 -0.189165 +-0.981945 0.000000 -0.189165 +-0.981945 0.000000 0.189165 +-0.981945 0.000000 0.189165 +-0.402924 0.000000 -0.915233 +-0.222515 0.000000 -0.974929 +-0.402924 0.000000 -0.915233 +-0.222515 0.000000 -0.974929 +-0.402924 0.000000 -0.915233 +-0.222515 0.000000 -0.974929 +-0.222519 0.000000 0.974928 +-0.402927 0.000000 0.915232 +-0.222519 0.000000 0.974928 +-0.402927 0.000000 0.915232 +-0.222519 0.000000 0.974928 +-0.402927 0.000000 0.915232 +0.698486 -0.449268 -0.557024 +0.623990 0.255936 -0.738332 +0.858674 0.255935 -0.444046 +0.698487 -0.449268 0.557023 +0.858672 0.255935 0.444049 +0.623986 0.255937 0.738334 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000004 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000004 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000003 +0.698486 -0.449268 -0.557024 +0.400738 -0.404834 -0.821900 +0.623990 0.255936 -0.738332 +0.400738 -0.404834 -0.821900 +0.416918 0.272435 -0.867156 +0.623990 0.255936 -0.738332 +0.890465 -0.404834 -0.207800 +0.858674 0.255935 -0.444046 +0.938188 0.272433 -0.213501 +0.858674 0.255935 -0.444046 +0.890465 -0.404834 -0.207800 +0.698486 -0.449268 -0.557024 +0.698487 -0.449268 0.557023 +0.890466 -0.404834 0.207799 +0.858672 0.255935 0.444049 +0.858672 0.255935 0.444049 +0.890466 -0.404834 0.207799 +0.938188 0.272433 0.213502 +0.400736 -0.404833 0.821901 +0.623986 0.255937 0.738334 +0.416915 0.272434 0.867157 +0.623986 0.255937 0.738334 +0.400736 -0.404833 0.821901 +0.698487 -0.449268 0.557023 +0.000000 1.000000 -0.000005 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000005 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000005 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.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.000002 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.574885 0.422775 0.700549 +-0.574885 0.422775 0.700549 +-0.389384 0.428931 0.815107 +-0.389384 0.428931 0.815107 +-0.390102 0.428945 0.814755 +-0.574885 0.422775 0.700549 +-0.881316 0.428930 0.198243 +-0.810908 0.422773 0.404587 +-0.881133 0.428945 0.199022 +-0.810908 0.422773 0.404587 +-0.881316 0.428930 0.198243 +-0.810908 0.422773 0.404587 +-0.810908 0.422774 -0.404586 +-0.810908 0.422774 -0.404586 +-0.881316 0.428931 -0.198242 +-0.810908 0.422774 -0.404586 +-0.881316 0.428931 -0.198242 +-0.881133 0.428946 -0.199021 +-0.389384 0.428929 -0.815107 +-0.574885 0.422774 -0.700549 +-0.390103 0.428944 -0.814755 +-0.574885 0.422774 -0.700549 +-0.389384 0.428929 -0.815107 +-0.574885 0.422774 -0.700549 +0.576228 0.381911 -0.722568 +0.377892 0.390141 -0.839635 +0.576228 0.381911 -0.722568 +0.377892 0.390141 -0.839635 +0.377892 0.390141 -0.839635 +0.576228 0.381911 -0.722568 +0.902674 0.390139 -0.181578 +0.832678 0.381908 -0.400992 +0.902674 0.390139 -0.181581 +0.832678 0.381908 -0.400992 +0.902674 0.390139 -0.181578 +0.832678 0.381908 -0.400992 +0.832674 0.381907 0.401000 +0.832674 0.381907 0.401000 +0.902673 0.390140 0.181582 +0.832674 0.381907 0.401000 +0.902673 0.390140 0.181582 +0.902673 0.390140 0.181584 +0.377892 0.390140 0.839636 +0.377892 0.390140 0.839636 +0.576229 0.381910 0.722569 +0.576229 0.381910 0.722569 +0.377892 0.390140 0.839636 +0.576229 0.381910 0.722569 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.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.000002 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000002 +0.000000 1.000000 -0.000001 +0.000000 1.000000 0.000002 +0.000000 1.000000 -0.000003 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000004 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000003 +0.000000 1.000000 0.000000 +-0.623493 0.000000 0.781829 +-0.402927 0.000000 0.915232 +-0.623493 0.000000 0.781829 +-0.402927 0.000000 0.915232 +-0.402927 0.000000 0.915232 +-0.623493 0.000000 0.781829 +-0.981945 0.000000 0.189165 +-0.981945 0.000000 0.189165 +-0.900970 0.000000 0.433882 +-0.981945 0.000000 0.189165 +-0.900970 0.000000 0.433882 +-0.900970 0.000000 0.433882 +-0.900968 0.000000 -0.433886 +-0.900968 0.000000 -0.433886 +-0.981945 0.000000 -0.189165 +-0.900968 0.000000 -0.433886 +-0.981945 0.000000 -0.189165 +-0.981945 0.000000 -0.189165 +-0.623493 0.000000 -0.781829 +-0.402924 0.000000 -0.915233 +-0.623493 0.000000 -0.781829 +-0.402924 0.000000 -0.915233 +-0.623493 0.000000 -0.781829 +-0.402924 0.000000 -0.915233 +0.277356 0.934962 -0.221179 +0.277356 0.934962 -0.221179 +0.277356 0.934962 -0.221179 +0.277356 0.934962 -0.221179 +0.277356 0.934962 -0.221179 +0.277356 0.934962 -0.221179 +-0.623492 0.000001 -0.781830 +-0.623492 0.000001 -0.781830 +-0.623492 0.000001 -0.781830 +-0.623492 0.000001 -0.781830 +-0.623492 0.000001 -0.781830 +-0.623492 0.000001 -0.781830 +0.623498 0.000003 0.781825 +0.623498 0.000003 0.781825 +0.623498 0.000003 0.781825 +0.623498 0.000003 0.781825 +0.623498 0.000003 0.781825 +0.623498 0.000003 0.781825 +0.277356 0.934960 0.221186 +0.277356 0.934960 0.221186 +0.277356 0.934960 0.221186 +0.277356 0.934960 0.221186 +0.277356 0.934960 0.221186 +0.277356 0.934960 0.221186 +-0.623495 -0.000001 0.781827 +-0.623495 -0.000001 0.781827 +-0.623495 -0.000001 0.781827 +-0.623495 -0.000001 0.781827 +-0.623495 -0.000001 0.781827 +-0.623495 -0.000001 0.781827 +0.623489 -0.000003 -0.781832 +0.623489 -0.000003 -0.781832 +0.623489 -0.000003 -0.781832 +0.623489 -0.000003 -0.781832 +0.623489 -0.000003 -0.781832 +0.623489 -0.000003 -0.781832 +0.623494 -0.000000 0.781828 +0.623494 -0.000000 0.781828 +0.623494 -0.000000 0.781828 +0.623494 -0.000000 0.781828 +0.623494 -0.000000 0.781828 +0.623494 -0.000000 0.781828 +-0.623491 0.000000 -0.781831 +-0.623491 0.000000 -0.781831 +-0.623491 0.000000 -0.781831 +-0.623491 0.000000 -0.781831 +-0.623491 0.000000 -0.781831 +-0.623491 0.000000 -0.781831 +0.105811 0.988708 -0.106117 +0.105811 0.988708 -0.106117 +0.105811 0.988708 -0.106117 +0.105811 0.988708 -0.106117 +0.105811 0.988708 -0.106117 +0.105811 0.988708 -0.106117 +0.623490 -0.000000 -0.781832 +0.623490 -0.000000 -0.781832 +0.623490 -0.000000 -0.781832 +0.623490 -0.000000 -0.781832 +0.623490 -0.000000 -0.781832 +0.623490 -0.000000 -0.781832 +0.105811 0.988708 0.106113 +0.105811 0.988708 0.106113 +0.105811 0.988708 0.106113 +0.105811 0.988708 0.106113 +0.105811 0.988708 0.106113 +0.105811 0.988708 0.106113 +-0.623491 0.000000 0.781831 +-0.623491 0.000000 0.781831 +-0.623491 0.000000 0.781831 +-0.623491 0.000000 0.781831 +-0.623491 0.000000 0.781831 +-0.623491 0.000000 0.781831 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.310861 -0.715334 -0.625830 +-0.698485 -0.449268 -0.557025 +-0.400738 -0.404834 -0.821900 +-0.698485 -0.449268 -0.557025 +-0.310861 -0.715334 -0.625830 +-0.549285 -0.711621 -0.438043 +-0.679313 -0.715333 0.163806 +-0.890466 -0.404833 0.207800 +-0.679313 -0.715332 -0.163808 +-0.890466 -0.404833 0.207800 +-0.890465 -0.404834 -0.207800 +-0.679313 -0.715332 -0.163808 +-0.698486 -0.449267 0.557025 +-0.890466 -0.404833 0.207800 +-0.679313 -0.715333 0.163806 +-0.698486 -0.449267 0.557025 +-0.679313 -0.715333 0.163806 +-0.549286 -0.711621 0.438041 +-0.310860 -0.715333 0.625831 +-0.000000 -0.394952 0.918702 +-0.400736 -0.404833 0.821901 +-0.000000 -0.394952 0.918702 +-0.310860 -0.715333 0.625831 +-0.000000 -0.715358 0.698758 +-0.400738 -0.404834 -0.821900 +-0.000000 -0.715359 -0.698757 +-0.310861 -0.715334 -0.625830 +-0.000000 -0.715359 -0.698757 +-0.400738 -0.404834 -0.821900 +-0.000000 -0.394954 -0.918701 +-0.698485 -0.449268 -0.557025 +-0.679313 -0.715332 -0.163808 +-0.890465 -0.404834 -0.207800 +-0.679313 -0.715332 -0.163808 +-0.698485 -0.449268 -0.557025 +-0.549285 -0.711621 -0.438043 +-0.310860 -0.715333 0.625831 +-0.698486 -0.449267 0.557025 +-0.549286 -0.711621 0.438041 +-0.698486 -0.449267 0.557025 +-0.310860 -0.715333 0.625831 +-0.400736 -0.404833 0.821901 +0.679314 -0.715333 0.163805 +0.890465 -0.404834 -0.207800 +0.890466 -0.404834 0.207799 +0.890465 -0.404834 -0.207800 +0.679314 -0.715333 0.163805 +0.679313 -0.715333 -0.163807 +-0.000000 -0.394952 0.918702 +0.310860 -0.715333 0.625832 +0.400736 -0.404833 0.821901 +0.310860 -0.715333 0.625832 +-0.000000 -0.394952 0.918702 +-0.000000 -0.715358 0.698758 +-0.000000 -0.715359 -0.698757 +0.400738 -0.404834 -0.821900 +0.310861 -0.715333 -0.625831 +0.400738 -0.404834 -0.821900 +-0.000000 -0.715359 -0.698757 +-0.000000 -0.394954 -0.918701 +0.698486 -0.449268 -0.557024 +0.310861 -0.715333 -0.625831 +0.400738 -0.404834 -0.821900 +0.310861 -0.715333 -0.625831 +0.698486 -0.449268 -0.557024 +0.549285 -0.711621 -0.438042 +0.679313 -0.715333 -0.163807 +0.698486 -0.449268 -0.557024 +0.890465 -0.404834 -0.207800 +0.698486 -0.449268 -0.557024 +0.679313 -0.715333 -0.163807 +0.549285 -0.711621 -0.438042 +0.698487 -0.449268 0.557023 +0.679314 -0.715333 0.163805 +0.890466 -0.404834 0.207799 +0.679314 -0.715333 0.163805 +0.698487 -0.449268 0.557023 +0.549287 -0.711622 0.438039 +0.310860 -0.715333 0.625832 +0.549287 -0.711622 0.438039 +0.698487 -0.449268 0.557023 +0.698487 -0.449268 0.557023 +0.400736 -0.404833 0.821901 +0.310860 -0.715333 0.625832 +0.972403 -0.000000 0.233307 +1.000000 -0.000000 -0.000000 +0.972403 -0.000000 0.233307 +1.000000 -0.000000 -0.000000 +0.972403 -0.000000 0.233307 +1.000000 -0.000000 -0.000000 +0.781832 -0.000000 0.623489 +0.972403 -0.000000 0.233307 +0.781832 -0.000000 0.623489 +0.972403 -0.000000 0.233307 +0.781832 -0.000000 0.623489 +0.972403 -0.000000 0.233307 +0.443837 -0.000000 0.896108 +0.781832 -0.000000 0.623489 +0.781832 -0.000000 0.623489 +0.781832 -0.000000 0.623489 +0.443837 -0.000000 0.896108 +0.443837 -0.000000 0.896108 +-0.000000 0.000000 1.000000 +0.443837 -0.000000 0.896108 +0.443837 -0.000000 0.896108 +0.443837 -0.000000 0.896108 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.443837 0.000000 0.896108 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.443837 0.000000 0.896108 +-0.443837 0.000000 0.896108 +-0.781832 0.000000 0.623489 +-0.443837 0.000000 0.896108 +-0.443837 0.000000 0.896108 +-0.443837 0.000000 0.896108 +-0.781832 0.000000 0.623489 +-0.781832 0.000000 0.623489 +-0.972403 0.000000 0.233307 +-0.972403 0.000000 0.233307 +-0.781832 0.000000 0.623489 +-0.781832 0.000000 0.623489 +-0.781832 0.000000 0.623489 +-0.972403 0.000000 0.233307 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.972403 0.000000 0.233307 +-0.972403 0.000000 0.233307 +-0.972403 0.000000 0.233307 +-1.000000 0.000000 -0.000000 +0.709329 0.420565 -0.565666 +0.709329 0.420565 -0.565666 +0.709329 0.420565 -0.565666 +-0.709329 0.420565 -0.565666 +-0.709329 0.420565 -0.565666 +-0.709329 0.420565 -0.565666 +-0.709328 0.420568 0.565665 +-0.709328 0.420568 0.565665 +-0.709328 0.420568 0.565665 +0.709327 0.420568 0.565665 +0.709327 0.420568 0.565665 +0.709327 0.420568 0.565665 +-0.671513 0.512145 -0.535517 +-0.525293 0.740664 -0.418909 +-0.381359 0.517350 -0.766103 +-0.381359 0.517350 -0.766103 +-0.525293 0.740664 -0.418909 +-0.300623 0.740044 -0.601632 +-0.831756 0.517350 0.201322 +-0.653442 0.740044 -0.159209 +-0.831755 0.517351 -0.201324 +-0.653442 0.740044 -0.159209 +-0.831756 0.517350 0.201322 +-0.653443 0.740044 0.159210 +-0.525294 0.740662 0.418909 +-0.831756 0.517350 0.201322 +-0.671515 0.512145 0.535515 +-0.831756 0.517350 0.201322 +-0.525294 0.740662 0.418909 +-0.653443 0.740044 0.159210 +-0.300625 0.740044 0.601631 +-0.000000 0.517385 0.855753 +-0.000000 0.741779 0.670645 +-0.000000 0.517385 0.855753 +-0.300625 0.740044 0.601631 +-0.381361 0.517351 0.766102 +-0.381359 0.517350 -0.766103 +-0.300623 0.740044 -0.601632 +0.000000 0.517384 -0.855754 +0.000000 0.517384 -0.855754 +-0.300623 0.740044 -0.601632 +0.000000 0.741780 -0.670644 +-0.831755 0.517351 -0.201324 +-0.525293 0.740664 -0.418909 +-0.671513 0.512145 -0.535517 +-0.525293 0.740664 -0.418909 +-0.831755 0.517351 -0.201324 +-0.653442 0.740044 -0.159209 +-0.525294 0.740662 0.418909 +-0.381361 0.517351 0.766102 +-0.300625 0.740044 0.601631 +-0.381361 0.517351 0.766102 +-0.525294 0.740662 0.418909 +-0.671515 0.512145 0.535515 +0.653443 0.740044 0.159211 +0.831756 0.517350 0.201323 +0.653442 0.740045 -0.159208 +0.831756 0.517350 0.201323 +0.831755 0.517351 -0.201323 +0.653442 0.740045 -0.159208 +0.300625 0.740043 0.601632 +-0.000000 0.741779 0.670645 +-0.000000 0.517385 0.855753 +-0.000000 0.517385 0.855753 +0.381360 0.517350 0.766103 +0.300625 0.740043 0.601632 +0.000000 0.517384 -0.855754 +0.300623 0.740044 -0.601632 +0.381359 0.517351 -0.766103 +0.300623 0.740044 -0.601632 +0.000000 0.517384 -0.855754 +0.000000 0.741780 -0.670644 +0.381359 0.517351 -0.766103 +0.525293 0.740664 -0.418908 +0.671513 0.512145 -0.535516 +0.525293 0.740664 -0.418908 +0.381359 0.517351 -0.766103 +0.300623 0.740044 -0.601632 +0.653442 0.740045 -0.159208 +0.831755 0.517351 -0.201323 +0.525293 0.740664 -0.418908 +0.831755 0.517351 -0.201323 +0.671513 0.512145 -0.535516 +0.525293 0.740664 -0.418908 +0.525294 0.740662 0.418911 +0.831756 0.517350 0.201323 +0.653443 0.740044 0.159211 +0.831756 0.517350 0.201323 +0.525294 0.740662 0.418911 +0.671513 0.512144 0.535517 +0.300625 0.740043 0.601632 +0.381360 0.517350 0.766103 +0.525294 0.740662 0.418911 +0.381360 0.517350 0.766103 +0.671513 0.512144 0.535517 +0.525294 0.740662 0.418911 +-0.300623 0.740044 -0.601632 +-0.525293 0.740664 -0.418909 +0.000000 1.000000 0.000001 +-0.653442 0.740044 -0.159209 +-0.653443 0.740044 0.159210 +0.000000 1.000000 0.000001 +-0.653443 0.740044 0.159210 +-0.525294 0.740662 0.418909 +0.000000 1.000000 0.000001 +-0.300625 0.740044 0.601631 +-0.000000 0.741779 0.670645 +0.000000 1.000000 0.000001 +0.000000 0.741780 -0.670644 +-0.300623 0.740044 -0.601632 +0.000000 1.000000 0.000001 +-0.525293 0.740664 -0.418909 +-0.653442 0.740044 -0.159209 +0.000000 1.000000 0.000001 +-0.525294 0.740662 0.418909 +-0.300625 0.740044 0.601631 +0.000000 1.000000 0.000001 +0.653443 0.740044 0.159211 +0.653442 0.740045 -0.159208 +0.000000 1.000000 0.000001 +-0.000000 0.741779 0.670645 +0.300625 0.740043 0.601632 +0.000000 1.000000 0.000001 +0.300623 0.740044 -0.601632 +0.000000 0.741780 -0.670644 +0.000000 1.000000 0.000001 +0.525293 0.740664 -0.418908 +0.300623 0.740044 -0.601632 +0.000000 1.000000 0.000001 +0.653442 0.740045 -0.159208 +0.525293 0.740664 -0.418908 +0.000000 1.000000 0.000001 +0.525294 0.740662 0.418911 +0.653443 0.740044 0.159211 +0.000000 1.000000 0.000001 +0.300625 0.740043 0.601632 +0.525294 0.740662 0.418911 +0.000000 1.000000 0.000001 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000007 +-0.000000 -1.000000 -0.000001 +-0.000000 -1.000000 0.000007 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000007 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -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 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.997975 0.000000 -0.063601 +-1.000000 0.000000 -0.000000 +-0.997975 0.000000 -0.063601 +-0.997975 0.000000 -0.063601 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.996621 -0.000000 0.082142 +0.996621 -0.000000 0.082142 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.996621 -0.000000 0.082142 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000003 +-0.382677 0.000000 -0.923882 +-0.033036 0.000000 -0.999454 +-0.017211 0.000000 -0.999852 +-0.382677 0.000000 -0.923882 +-0.382677 0.000000 -0.923882 +-0.033036 0.000000 -0.999454 +-0.033036 0.000000 -0.999454 +-0.382677 0.000000 -0.923882 +-0.382677 0.000000 -0.923882 +-0.997975 0.000000 -0.063601 +-0.923881 0.000000 -0.382680 +-0.997975 0.000000 -0.063601 +-0.923881 0.000000 -0.382680 +-0.997975 0.000000 -0.063601 +-0.923881 0.000000 -0.382680 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000005 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000005 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.382674 -0.000000 0.923884 +0.017060 -0.000000 0.999854 +0.017060 -0.000000 0.999854 +0.017060 -0.000000 0.999854 +0.382674 -0.000000 0.923884 +0.382674 -0.000000 0.923884 +0.923880 -0.000000 0.382682 +0.923880 -0.000000 0.382682 +0.996621 -0.000000 0.082142 +0.996621 -0.000000 0.082142 +0.996621 -0.000000 0.082142 +0.923880 -0.000000 0.382682 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.997975 -0.000000 -0.063601 +0.997975 -0.000000 -0.063601 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.997975 -0.000000 -0.063601 +-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.000000 +0.000000 1.000000 -0.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 +-1.000000 0.000000 -0.000000 +-0.996621 0.000000 0.082142 +-1.000000 0.000000 -0.000000 +-0.996621 0.000000 0.082142 +-1.000000 0.000000 -0.000000 +-0.996621 0.000000 0.082142 +0.017060 -0.000000 0.999854 +-0.017060 0.000000 0.999854 +-0.017060 0.000000 0.999854 +-0.017060 0.000000 0.999854 +0.017060 -0.000000 0.999854 +0.017060 -0.000000 0.999854 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000003 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000003 +-0.000000 -1.000000 0.000003 +0.017211 -0.000000 -0.999852 +-0.033036 0.000000 -0.999454 +0.033036 -0.000000 -0.999454 +-0.033036 0.000000 -0.999454 +0.017211 -0.000000 -0.999852 +-0.017211 0.000000 -0.999852 +0.000000 1.000000 0.000005 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000006 +0.000000 1.000000 0.000005 +0.000000 1.000000 0.000005 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 -0.000001 +-0.000000 -1.000000 0.000001 +-0.000000 -1.000000 0.000001 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 0.000003 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 -0.000001 +0.017211 -0.000000 -0.999852 +0.033036 -0.000000 -0.999454 +0.382681 -0.000000 -0.923881 +0.382681 -0.000000 -0.923881 +0.382681 -0.000000 -0.923881 +0.033036 -0.000000 -0.999454 +0.033036 -0.000000 -0.999454 +0.382681 -0.000000 -0.923881 +0.382681 -0.000000 -0.923881 +0.923881 -0.000000 -0.382680 +0.923881 -0.000000 -0.382680 +0.997975 -0.000000 -0.063601 +0.997975 -0.000000 -0.063601 +0.997975 -0.000000 -0.063601 +0.923881 -0.000000 -0.382680 +0.000000 1.000000 0.000005 +0.000000 1.000000 0.000006 +0.000000 1.000000 -0.000001 +0.000000 1.000000 0.000005 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000002 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000001 +0.000000 1.000000 -0.000000 +-0.017060 0.000000 0.999854 +-0.382674 0.000000 0.923884 +-0.382674 0.000000 0.923884 +-0.382674 0.000000 0.923884 +-0.017060 0.000000 0.999854 +-0.017060 0.000000 0.999854 +-0.996621 0.000000 0.082142 +-0.923880 0.000000 0.382682 +-0.996621 0.000000 0.082142 +-0.923880 0.000000 0.382682 +-0.996621 0.000000 0.082142 +-0.923880 0.000000 0.382682 +0.175033 -0.000000 -0.984563 +-0.175033 0.000000 -0.984563 +-0.175033 0.000000 -0.984563 +0.175033 -0.000000 -0.984563 +-0.175033 0.000000 -0.984563 +0.175033 -0.000000 -0.984563 +-0.618952 0.000000 -0.785429 +-0.831620 0.000000 -0.555346 +-0.831620 0.000000 -0.555346 +-0.831620 0.000000 -0.555346 +-0.618952 0.000000 -0.785429 +-0.618952 0.000000 -0.785429 +0.000000 1.000000 -0.000004 +0.000000 1.000000 -0.000004 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000004 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000003 +0.618952 -0.000000 -0.785429 +0.831620 -0.000000 -0.555346 +0.831620 -0.000000 -0.555346 +0.831620 -0.000000 -0.555346 +0.618952 -0.000000 -0.785429 +0.618952 -0.000000 -0.785429 +-0.000000 -1.000000 -0.000004 +-0.000000 -1.000000 -0.000004 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 -0.000004 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 -0.000002 +-0.175033 0.000000 -0.984563 +-0.618952 0.000000 -0.785429 +-0.618952 0.000000 -0.785429 +-0.175033 0.000000 -0.984563 +-0.618952 0.000000 -0.785429 +-0.175033 0.000000 -0.984563 +0.618952 -0.000000 -0.785429 +0.175033 -0.000000 -0.984563 +0.175033 -0.000000 -0.984563 +0.618952 -0.000000 -0.785429 +0.175033 -0.000000 -0.984563 +0.618952 -0.000000 -0.785429 +0.000000 1.000000 -0.000003 +0.000000 1.000000 -0.000003 +0.000000 1.000000 0.000004 +0.000000 1.000000 0.000004 +0.000000 1.000000 -0.000003 +0.000000 1.000000 0.000004 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 0.000008 +-0.000000 -1.000000 0.000008 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 0.000008 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 -0.000002 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 0.000002 +-0.000000 -1.000000 -0.000001 +-0.000000 0.642787 0.766045 +-0.000000 0.642787 0.766045 +0.000000 0.995943 0.089983 +-0.000000 0.642787 0.766045 +0.000000 0.995943 0.089983 +0.000000 0.995943 0.089983 +0.000000 1.000000 0.000000 +0.000000 0.995943 0.089983 +0.000000 0.995943 0.089983 +0.000000 0.995943 0.089983 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 -0.995943 0.089985 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -0.995943 0.089985 +-0.000000 -0.995943 0.089985 +-0.000000 -0.642788 0.766044 +-0.000000 -0.995943 0.089985 +-0.000000 -0.642788 0.766044 +-0.000000 -0.995943 0.089985 +-0.000000 -0.642788 0.766044 +-0.000000 -0.995943 0.089985 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.642787 0.766045 +-0.000000 0.000000 1.000000 +-0.000000 0.642787 0.766045 +-0.000000 0.000000 1.000000 +-0.000000 0.642787 0.766045 +-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.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.984810 0.173635 +-0.000000 0.642787 0.766045 +-0.000000 0.642787 0.766045 +-0.000000 0.642787 0.766045 +0.000000 0.984810 0.173635 +0.000000 0.984810 0.173635 +0.000000 0.866027 -0.499998 +0.000000 0.984810 0.173635 +0.000000 0.984810 0.173635 +0.000000 0.984810 0.173635 +0.000000 0.866027 -0.499998 +0.000000 0.866027 -0.499998 +0.000000 0.342027 -0.939690 +0.000000 0.866027 -0.499998 +0.000000 0.342027 -0.939690 +0.000000 0.866027 -0.499998 +0.000000 0.342027 -0.939690 +0.000000 0.866027 -0.499998 +0.000000 -0.342021 -0.939692 +0.000000 0.342027 -0.939690 +0.000000 -0.342021 -0.939692 +0.000000 0.342027 -0.939690 +0.000000 -0.342021 -0.939692 +0.000000 0.342027 -0.939690 +-0.000000 -0.866025 -0.500000 +0.000000 -0.342021 -0.939692 +-0.000000 -0.866025 -0.500000 +0.000000 -0.342021 -0.939692 +-0.000000 -0.866025 -0.500000 +0.000000 -0.342021 -0.939692 +-0.000000 -0.984806 0.173656 +-0.000000 -0.866025 -0.500000 +-0.000000 -0.866025 -0.500000 +-0.000000 -0.866025 -0.500000 +-0.000000 -0.984806 0.173656 +-0.000000 -0.984806 0.173656 +-0.000000 -0.642790 0.766042 +-0.000000 -0.984806 0.173656 +-0.000000 -0.642790 0.766042 +-0.000000 -0.984806 0.173656 +-0.000000 -0.642790 0.766042 +-0.000000 -0.984806 0.173656 +-0.000000 -0.000000 1.000000 +-0.000000 -0.642790 0.766042 +-0.000000 -0.000000 1.000000 +-0.000000 -0.642790 0.766042 +-0.000000 -0.000000 1.000000 +-0.000000 -0.642790 0.766042 +-0.000000 0.642787 0.766045 +-0.000000 -0.000000 1.000000 +-0.000000 0.642787 0.766045 +-0.000000 -0.000000 1.000000 +-0.000000 0.642787 0.766045 +-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.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-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.984808 0.173649 +0.000000 0.984808 0.173649 +-0.000000 0.642793 0.766040 +-0.000000 0.642793 0.766040 +-0.000000 0.642793 0.766040 +0.000000 0.984808 0.173649 +0.000000 0.866031 -0.499990 +0.000000 0.866031 -0.499990 +0.000000 0.984808 0.173649 +0.000000 0.984808 0.173649 +0.000000 0.984808 0.173649 +0.000000 0.866031 -0.499990 +0.000000 0.342018 -0.939693 +0.000000 0.866031 -0.499990 +0.000000 0.342018 -0.939693 +0.000000 0.866031 -0.499990 +0.000000 0.342018 -0.939693 +0.000000 0.866031 -0.499990 +0.000000 -0.342020 -0.939693 +0.000000 0.342018 -0.939693 +0.000000 -0.342020 -0.939693 +0.000000 0.342018 -0.939693 +0.000000 -0.342020 -0.939693 +0.000000 0.342018 -0.939693 +-0.000000 -0.866026 -0.499999 +0.000000 -0.342020 -0.939693 +-0.000000 -0.866026 -0.499999 +0.000000 -0.342020 -0.939693 +-0.000000 -0.866026 -0.499999 +0.000000 -0.342020 -0.939693 +-0.000000 -0.984807 0.173655 +-0.000000 -0.866026 -0.499999 +-0.000000 -0.984807 0.173655 +-0.000000 -0.866026 -0.499999 +-0.000000 -0.984807 0.173655 +-0.000000 -0.866026 -0.499999 +-0.000000 -0.642788 0.766044 +-0.000000 -0.984807 0.173655 +-0.000000 -0.984807 0.173655 +-0.000000 -0.984807 0.173655 +-0.000000 -0.642788 0.766044 +-0.000000 -0.642788 0.766044 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.642793 0.766040 +-0.000000 0.000000 1.000000 +-0.000000 0.642793 0.766040 +-0.000000 0.000000 1.000000 +-0.000000 0.642793 0.766040 +-0.000000 0.000000 1.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 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.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.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.000001 0.000000 +-1.000000 -0.000001 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.000000 0.000000 +0.000000 0.995943 -0.089983 +0.000000 0.995943 -0.089983 +0.000000 0.642787 -0.766045 +0.000000 0.995943 -0.089983 +0.000000 0.642787 -0.766045 +0.000000 0.642787 -0.766045 +0.000000 1.000000 0.000000 +0.000000 0.995943 -0.089983 +0.000000 1.000000 0.000000 +0.000000 0.995943 -0.089983 +0.000000 1.000000 0.000000 +0.000000 0.995943 -0.089983 +-0.000000 -1.000000 -0.000000 +-0.000000 -0.995943 -0.089985 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -0.995943 -0.089985 +-0.000000 -0.995943 -0.089985 +0.000000 -0.642788 -0.766044 +-0.000000 -0.995943 -0.089985 +-0.000000 -0.995943 -0.089985 +-0.000000 -0.995943 -0.089985 +0.000000 -0.642788 -0.766044 +0.000000 -0.642788 -0.766044 +0.000000 -0.642788 -0.766044 +0.000000 -0.000000 -1.000000 +0.000000 -0.642788 -0.766044 +0.000000 -0.642788 -0.766044 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642787 -0.766045 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642787 -0.766045 +0.000000 0.642787 -0.766045 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.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.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -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.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.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.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.000001 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000001 -0.000000 +0.000000 0.984810 -0.173636 +0.000000 0.642787 -0.766045 +0.000000 0.984810 -0.173636 +0.000000 0.984810 -0.173636 +0.000000 0.642787 -0.766045 +0.000000 0.642787 -0.766045 +0.000000 0.866027 0.499998 +0.000000 0.984810 -0.173636 +0.000000 0.866027 0.499998 +0.000000 0.984810 -0.173636 +0.000000 0.866027 0.499998 +0.000000 0.984810 -0.173636 +-0.000000 0.342027 0.939690 +0.000000 0.866027 0.499998 +0.000000 0.866027 0.499998 +0.000000 0.866027 0.499998 +-0.000000 0.342027 0.939690 +-0.000000 0.342027 0.939690 +-0.000000 -0.342021 0.939692 +-0.000000 0.342027 0.939690 +-0.000000 0.342027 0.939690 +-0.000000 0.342027 0.939690 +-0.000000 -0.342021 0.939692 +-0.000000 -0.342021 0.939692 +-0.000000 -0.342021 0.939692 +-0.000000 -0.866025 0.500001 +-0.000000 -0.342021 0.939692 +-0.000000 -0.342021 0.939692 +-0.000000 -0.866025 0.500001 +-0.000000 -0.866025 0.500001 +-0.000000 -0.866025 0.500001 +-0.000000 -0.984806 -0.173656 +-0.000000 -0.866025 0.500001 +-0.000000 -0.866025 0.500001 +-0.000000 -0.984806 -0.173656 +-0.000000 -0.984806 -0.173656 +-0.000000 -0.984806 -0.173656 +0.000000 -0.642790 -0.766042 +-0.000000 -0.984806 -0.173656 +-0.000000 -0.984806 -0.173656 +0.000000 -0.642790 -0.766042 +0.000000 -0.642790 -0.766042 +0.000000 -0.642790 -0.766042 +0.000000 -0.000000 -1.000000 +0.000000 -0.642790 -0.766042 +0.000000 -0.642790 -0.766042 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642787 -0.766045 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642787 -0.766045 +0.000000 0.642787 -0.766045 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.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.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.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.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.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.984807 -0.173650 +0.000000 0.642793 -0.766040 +0.000000 0.984807 -0.173650 +0.000000 0.642793 -0.766040 +0.000000 0.984807 -0.173650 +0.000000 0.642793 -0.766040 +0.000000 0.866031 0.499990 +0.000000 0.866031 0.499990 +0.000000 0.984807 -0.173650 +0.000000 0.866031 0.499990 +0.000000 0.984807 -0.173650 +0.000000 0.984807 -0.173650 +0.000000 0.866031 0.499990 +0.000000 0.866031 0.499990 +-0.000000 0.342017 0.939694 +0.000000 0.866031 0.499990 +-0.000000 0.342017 0.939694 +-0.000000 0.342017 0.939694 +-0.000000 0.342017 0.939694 +-0.000000 0.342017 0.939694 +-0.000000 -0.342019 0.939693 +-0.000000 0.342017 0.939694 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.866026 0.499999 +-0.000000 -0.342019 0.939693 +-0.000000 -0.866026 0.499999 +-0.000000 -0.866026 0.499999 +-0.000000 -0.866026 0.499999 +-0.000000 -0.866026 0.499999 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.866026 0.499999 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +0.000000 -0.642787 -0.766045 +-0.000000 -0.984807 -0.173655 +0.000000 -0.642787 -0.766045 +0.000000 -0.642787 -0.766045 +0.000000 -0.642787 -0.766045 +0.000000 -0.642787 -0.766045 +0.000000 -0.000000 -1.000000 +0.000000 -0.642787 -0.766045 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642793 -0.766040 +0.000000 -0.000000 -1.000000 +0.000000 0.642793 -0.766040 +0.000000 0.642793 -0.766040 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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.642787 0.766045 +0.000000 0.995943 0.089983 +-0.000000 0.642787 0.766045 +-0.000000 0.642787 0.766045 +0.000000 0.995943 0.089983 +0.000000 0.995943 0.089983 +0.000000 0.995943 0.089983 +0.000000 1.000000 0.000000 +0.000000 0.995943 0.089983 +0.000000 0.995943 0.089983 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 -0.995943 0.089985 +-0.000000 -1.000000 -0.000000 +-0.000000 -0.995943 0.089985 +-0.000000 -0.995943 0.089985 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -0.642788 0.766044 +-0.000000 -0.642788 0.766044 +-0.000000 -0.995943 0.089985 +-0.000000 -0.642788 0.766044 +-0.000000 -0.995943 0.089985 +-0.000000 -0.995943 0.089985 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 -0.642788 0.766044 +-0.000000 0.642787 0.766045 +-0.000000 0.000000 1.000000 +-0.000000 0.642787 0.766045 +-0.000000 0.000000 1.000000 +-0.000000 0.642787 0.766045 +-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.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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.642787 0.766045 +0.000000 0.984810 0.173635 +-0.000000 0.642787 0.766045 +-0.000000 0.642787 0.766045 +0.000000 0.984810 0.173635 +0.000000 0.984810 0.173635 +0.000000 0.984810 0.173635 +0.000000 0.866027 -0.499998 +0.000000 0.984810 0.173635 +0.000000 0.984810 0.173635 +0.000000 0.866027 -0.499998 +0.000000 0.866027 -0.499998 +0.000000 0.342027 -0.939690 +0.000000 0.866027 -0.499998 +0.000000 0.342027 -0.939690 +0.000000 0.342027 -0.939690 +0.000000 0.866027 -0.499998 +0.000000 0.866027 -0.499998 +0.000000 -0.342021 -0.939692 +0.000000 0.342027 -0.939690 +0.000000 -0.342021 -0.939692 +0.000000 -0.342021 -0.939692 +0.000000 0.342027 -0.939690 +0.000000 0.342027 -0.939690 +-0.000000 -0.866025 -0.500000 +0.000000 -0.342021 -0.939692 +-0.000000 -0.866025 -0.500000 +-0.000000 -0.866025 -0.500000 +0.000000 -0.342021 -0.939692 +0.000000 -0.342021 -0.939692 +-0.000000 -0.984806 0.173656 +-0.000000 -0.866025 -0.500000 +-0.000000 -0.984806 0.173656 +-0.000000 -0.984806 0.173656 +-0.000000 -0.866025 -0.500000 +-0.000000 -0.866025 -0.500000 +-0.000000 -0.642790 0.766042 +-0.000000 -0.984806 0.173656 +-0.000000 -0.642790 0.766042 +-0.000000 -0.642790 0.766042 +-0.000000 -0.984806 0.173656 +-0.000000 -0.984806 0.173656 +-0.000000 -0.000000 1.000000 +-0.000000 -0.642790 0.766042 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.642790 0.766042 +-0.000000 -0.642790 0.766042 +-0.000000 0.642787 0.766045 +-0.000000 -0.000000 1.000000 +-0.000000 0.642787 0.766045 +-0.000000 -0.000000 1.000000 +-0.000000 0.642787 0.766045 +-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.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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.642793 0.766040 +-0.000000 0.642793 0.766040 +0.000000 0.984808 0.173649 +-0.000000 0.642793 0.766040 +0.000000 0.984808 0.173649 +0.000000 0.984808 0.173649 +0.000000 0.866031 -0.499990 +0.000000 0.984808 0.173649 +0.000000 0.984808 0.173649 +0.000000 0.984808 0.173649 +0.000000 0.866031 -0.499990 +0.000000 0.866031 -0.499990 +0.000000 0.342018 -0.939693 +0.000000 0.342018 -0.939693 +0.000000 0.866031 -0.499990 +0.000000 0.342018 -0.939693 +0.000000 0.866031 -0.499990 +0.000000 0.866031 -0.499990 +0.000000 -0.342020 -0.939693 +0.000000 -0.342020 -0.939693 +0.000000 0.342018 -0.939693 +0.000000 -0.342020 -0.939693 +0.000000 0.342018 -0.939693 +0.000000 0.342018 -0.939693 +-0.000000 -0.866026 -0.499999 +-0.000000 -0.866026 -0.499999 +0.000000 -0.342020 -0.939693 +-0.000000 -0.866026 -0.499999 +0.000000 -0.342020 -0.939693 +0.000000 -0.342020 -0.939693 +-0.000000 -0.984807 0.173655 +-0.000000 -0.984807 0.173655 +-0.000000 -0.866026 -0.499999 +-0.000000 -0.984807 0.173655 +-0.000000 -0.866026 -0.499999 +-0.000000 -0.866026 -0.499999 +-0.000000 -0.642788 0.766044 +-0.000000 -0.642788 0.766044 +-0.000000 -0.984807 0.173655 +-0.000000 -0.642788 0.766044 +-0.000000 -0.984807 0.173655 +-0.000000 -0.984807 0.173655 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.000000 1.000000 +-0.000000 -0.642788 0.766044 +-0.000000 0.642793 0.766040 +-0.000000 0.642793 0.766040 +-0.000000 0.000000 1.000000 +-0.000000 0.642793 0.766040 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +1.000000 0.000001 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.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.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.000001 0.000000 +1.000000 -0.000001 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.000001 0.000000 +0.000000 0.995943 -0.089983 +0.000000 0.642787 -0.766045 +0.000000 0.995943 -0.089983 +0.000000 0.642787 -0.766045 +0.000000 0.995943 -0.089983 +0.000000 0.642787 -0.766045 +0.000000 1.000000 0.000000 +0.000000 0.995943 -0.089983 +0.000000 1.000000 0.000000 +0.000000 0.995943 -0.089983 +0.000000 1.000000 0.000000 +0.000000 0.995943 -0.089983 +-0.000000 -0.995943 -0.089985 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -0.995943 -0.089985 +-0.000000 -0.995943 -0.089985 +-0.000000 -0.995943 -0.089985 +-0.000000 -0.995943 -0.089985 +0.000000 -0.642788 -0.766044 +-0.000000 -0.995943 -0.089985 +0.000000 -0.642788 -0.766044 +0.000000 -0.642788 -0.766044 +0.000000 -0.642788 -0.766044 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.642788 -0.766044 +0.000000 -0.642788 -0.766044 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642787 -0.766045 +0.000000 -0.000000 -1.000000 +0.000000 0.642787 -0.766045 +0.000000 0.642787 -0.766045 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.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.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 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.000001 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.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.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.000001 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000001 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.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.000001 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.984810 -0.173636 +0.000000 0.642787 -0.766045 +0.000000 0.984810 -0.173636 +0.000000 0.642787 -0.766045 +0.000000 0.984810 -0.173636 +0.000000 0.642787 -0.766045 +0.000000 0.866027 0.499998 +0.000000 0.984810 -0.173636 +0.000000 0.866027 0.499998 +0.000000 0.984810 -0.173636 +0.000000 0.866027 0.499998 +0.000000 0.984810 -0.173636 +-0.000000 0.342027 0.939690 +0.000000 0.866027 0.499998 +0.000000 0.866027 0.499998 +0.000000 0.866027 0.499998 +-0.000000 0.342027 0.939690 +-0.000000 0.342027 0.939690 +-0.000000 -0.342021 0.939692 +-0.000000 0.342027 0.939690 +-0.000000 0.342027 0.939690 +-0.000000 0.342027 0.939690 +-0.000000 -0.342021 0.939692 +-0.000000 -0.342021 0.939692 +-0.000000 -0.866025 0.500001 +-0.000000 -0.342021 0.939692 +-0.000000 -0.342021 0.939692 +-0.000000 -0.342021 0.939692 +-0.000000 -0.866025 0.500001 +-0.000000 -0.866025 0.500001 +-0.000000 -0.984806 -0.173656 +-0.000000 -0.866025 0.500001 +-0.000000 -0.866025 0.500001 +-0.000000 -0.866025 0.500001 +-0.000000 -0.984806 -0.173656 +-0.000000 -0.984806 -0.173656 +0.000000 -0.642790 -0.766042 +-0.000000 -0.984806 -0.173656 +-0.000000 -0.984806 -0.173656 +-0.000000 -0.984806 -0.173656 +0.000000 -0.642790 -0.766042 +0.000000 -0.642790 -0.766042 +0.000000 -0.642790 -0.766042 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.642790 -0.766042 +0.000000 -0.642790 -0.766042 +0.000000 0.642787 -0.766045 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642787 -0.766045 +0.000000 0.642787 -0.766045 +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.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.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.000001 -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.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.000000 +1.000000 -0.000001 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.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.000000 +1.000000 0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +0.000000 0.984807 -0.173650 +0.000000 0.642793 -0.766040 +0.000000 0.984807 -0.173650 +0.000000 0.642793 -0.766040 +0.000000 0.984807 -0.173650 +0.000000 0.642793 -0.766040 +0.000000 0.866031 0.499990 +0.000000 0.984807 -0.173650 +0.000000 0.866031 0.499990 +0.000000 0.984807 -0.173650 +0.000000 0.866031 0.499990 +0.000000 0.984807 -0.173650 +-0.000000 0.342017 0.939694 +-0.000000 0.342017 0.939694 +0.000000 0.866031 0.499990 +0.000000 0.866031 0.499990 +0.000000 0.866031 0.499990 +-0.000000 0.342017 0.939694 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 0.342017 0.939694 +-0.000000 0.342017 0.939694 +-0.000000 0.342017 0.939694 +-0.000000 -0.342019 0.939693 +-0.000000 -0.866026 0.499999 +-0.000000 -0.866026 0.499999 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.866026 0.499999 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.866026 0.499999 +-0.000000 -0.866026 0.499999 +-0.000000 -0.866026 0.499999 +-0.000000 -0.984807 -0.173655 +0.000000 -0.642787 -0.766045 +0.000000 -0.642787 -0.766045 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +0.000000 -0.642787 -0.766045 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.642787 -0.766045 +0.000000 -0.642787 -0.766045 +0.000000 -0.642787 -0.766045 +0.000000 -0.000000 -1.000000 +0.000000 0.642793 -0.766040 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642793 -0.766040 +0.000000 0.642793 -0.766040 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-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.984807 -0.173651 +0.000000 0.642793 -0.766040 +0.000000 0.984807 -0.173651 +0.000000 0.642793 -0.766040 +0.000000 0.984807 -0.173651 +0.000000 0.642793 -0.766040 +0.000000 0.866030 0.499991 +0.000000 0.984807 -0.173651 +0.000000 0.866030 0.499991 +0.000000 0.984807 -0.173651 +0.000000 0.866030 0.499991 +0.000000 0.984807 -0.173651 +-0.000000 0.342018 0.939693 +-0.000000 0.342018 0.939693 +0.000000 0.866030 0.499991 +0.000000 0.866030 0.499991 +0.000000 0.866030 0.499991 +-0.000000 0.342018 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 0.342018 0.939693 +-0.000000 0.342018 0.939693 +-0.000000 0.342018 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.866023 0.500003 +-0.000000 -0.866023 0.500003 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.342019 0.939693 +-0.000000 -0.866023 0.500003 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.866023 0.500003 +-0.000000 -0.866023 0.500003 +-0.000000 -0.866023 0.500003 +-0.000000 -0.984807 -0.173655 +0.000000 -0.642786 -0.766046 +0.000000 -0.642786 -0.766046 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +-0.000000 -0.984807 -0.173655 +0.000000 -0.642786 -0.766046 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.642786 -0.766046 +0.000000 -0.642786 -0.766046 +0.000000 -0.642786 -0.766046 +0.000000 -0.000000 -1.000000 +0.000000 0.642793 -0.766040 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.642793 -0.766040 +0.000000 0.642793 -0.766040 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-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.274257 0.961656 +-0.000000 -0.274257 0.961656 +-0.000000 -0.274257 0.961656 +-0.000000 0.000000 1.000000 +-0.000000 -0.923358 0.383939 +-0.000000 -0.923358 0.383939 +-0.000000 -0.996907 0.078596 +-0.000000 -0.996907 0.078596 +-0.000000 -0.996907 0.078596 +-0.000000 -0.923358 0.383939 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.293119 -0.956076 +0.000000 0.000000 -1.000000 +0.000000 0.293119 -0.956076 +0.000000 0.293119 -0.956076 +0.000000 0.932661 -0.360754 +0.000000 0.999914 -0.013093 +0.000000 0.999914 -0.013093 +0.000000 0.999914 -0.013093 +0.000000 0.932661 -0.360754 +0.000000 0.932661 -0.360754 +0.000000 0.883673 0.468106 +0.000000 0.883673 0.468106 +0.000000 0.983389 0.181510 +0.000000 0.883673 0.468106 +0.000000 0.983389 0.181510 +0.000000 0.983389 0.181510 +0.000000 0.883673 0.468106 +-0.000000 0.454064 0.890969 +0.000000 0.883673 0.468106 +-0.000000 0.454064 0.890969 +0.000000 0.883673 0.468106 +-0.000000 0.454064 0.890969 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +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.565058 -0.825051 +0.000000 -0.565058 -0.825051 +-0.000000 -0.898050 -0.439893 +0.000000 -0.565058 -0.825051 +-0.000000 -0.898050 -0.439893 +-0.000000 -0.898050 -0.439893 +-0.000000 -0.898050 -0.439893 +-0.000000 -0.898050 -0.439893 +-0.000000 -0.996832 -0.079531 +-0.000000 -0.898050 -0.439893 +-0.000000 -0.996832 -0.079531 +-0.000000 -0.996832 -0.079531 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-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.996832 -0.079531 +-0.000000 -0.996832 -0.079531 +-0.000000 -0.996907 0.078596 +-0.000000 -0.996832 -0.079531 +-0.000000 -0.996907 0.078596 +-0.000000 -0.996907 0.078596 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +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.983389 0.181510 +0.000000 0.983389 0.181510 +0.000000 0.999914 -0.013093 +0.000000 0.983389 0.181510 +0.000000 0.999914 -0.013093 +0.000000 0.999914 -0.013093 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-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.565058 -0.825051 +0.000000 0.000000 -1.000000 +0.000000 -0.565058 -0.825051 +0.000000 -0.565058 -0.825051 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +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.454064 0.890969 +-0.000000 0.454064 0.890969 +-0.000000 0.000000 1.000000 +-0.000000 0.454064 0.890969 +-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.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-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.565053 -0.825054 +0.000000 0.898050 -0.439893 +0.000000 0.565053 -0.825054 +0.000000 0.898050 -0.439893 +0.000000 0.565053 -0.825054 +0.000000 0.898050 -0.439893 +0.000000 0.898050 -0.439893 +0.000000 0.996832 -0.079531 +0.000000 0.898050 -0.439893 +0.000000 0.996832 -0.079531 +0.000000 0.898050 -0.439893 +0.000000 0.996832 -0.079531 +0.000000 -0.293118 -0.956076 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.293118 -0.956076 +0.000000 -0.293118 -0.956076 +-0.000000 -0.999914 -0.013093 +-0.000000 -0.999914 -0.013093 +-0.000000 -0.932662 -0.360751 +-0.000000 -0.999914 -0.013093 +-0.000000 -0.932662 -0.360751 +-0.000000 -0.932662 -0.360751 +-0.000000 -0.983390 0.181507 +-0.000000 -0.983390 0.181507 +-0.000000 -0.883673 0.468106 +-0.000000 -0.883673 0.468106 +-0.000000 -0.883673 0.468106 +-0.000000 -0.983390 0.181507 +-0.000000 -0.883673 0.468106 +-0.000000 -0.883673 0.468106 +-0.000000 -0.454061 0.890971 +-0.000000 -0.454061 0.890971 +-0.000000 -0.454061 0.890971 +-0.000000 -0.883673 0.468106 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +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.274254 0.961657 +-0.000000 0.000000 1.000000 +-0.000000 0.274254 0.961657 +-0.000000 0.000000 1.000000 +-0.000000 0.274254 0.961657 +0.000000 0.923358 0.383939 +0.000000 0.923358 0.383939 +0.000000 0.996907 0.078596 +0.000000 0.996907 0.078596 +0.000000 0.996907 0.078596 +0.000000 0.923358 0.383939 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-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.996832 -0.079531 +0.000000 0.996907 0.078596 +0.000000 0.996832 -0.079531 +0.000000 0.996907 0.078596 +0.000000 0.996832 -0.079531 +0.000000 0.996907 0.078596 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +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.983390 0.181507 +-0.000000 -0.999914 -0.013093 +-0.000000 -0.983390 0.181507 +-0.000000 -0.983390 0.181507 +-0.000000 -0.999914 -0.013093 +-0.000000 -0.999914 -0.013093 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-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.565053 -0.825054 +0.000000 0.565053 -0.825054 +0.000000 0.565053 -0.825054 +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.454061 0.890971 +-0.000000 -0.454061 0.890971 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 -0.454061 0.890971 +0.000000 -0.159313 -0.987228 +0.000000 0.159313 -0.987228 +0.000000 -0.159313 -0.987228 +0.000000 0.159313 -0.987228 +0.000000 -0.159313 -0.987228 +0.000000 0.159313 -0.987228 +-0.000000 -1.000000 0.000000 +-0.000000 -0.995975 -0.089635 +-0.000000 -0.995975 -0.089635 +-0.000000 -0.995975 -0.089635 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.000000 -0.306334 -0.951924 +0.000000 -0.159313 -0.987228 +0.000000 -0.306334 -0.951924 +0.000000 -0.159313 -0.987228 +0.000000 -0.306334 -0.951924 +0.000000 -0.159313 -0.987228 +-0.000000 -0.995975 -0.089635 +-0.000000 -0.882415 -0.470472 +-0.000000 -0.995975 -0.089635 +-0.000000 -0.882415 -0.470472 +-0.000000 -0.995975 -0.089635 +-0.000000 -0.882415 -0.470472 +0.000000 0.882418 -0.470466 +0.000000 0.882418 -0.470466 +0.000000 0.998166 -0.060531 +0.000000 0.998166 -0.060531 +0.000000 0.998166 -0.060531 +0.000000 0.882418 -0.470466 +0.000000 0.159313 -0.987228 +0.000000 0.306334 -0.951924 +0.000000 0.159313 -0.987228 +0.000000 0.306334 -0.951924 +0.000000 0.159313 -0.987228 +0.000000 0.306334 -0.951924 +0.000000 1.000000 0.000000 +0.000000 0.998166 -0.060531 +0.000000 1.000000 0.000000 +0.000000 0.998166 -0.060531 +0.000000 1.000000 0.000000 +0.000000 0.998166 -0.060531 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-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.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 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-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 +-0.851014 0.313486 0.421308 +-0.497049 0.618083 0.609028 +-0.497051 0.618083 0.609028 +-0.497049 0.618083 0.609028 +-0.851014 0.313486 0.421308 +-0.851016 0.313484 0.421307 +-0.978815 -0.106370 0.174947 +-0.851016 0.313484 0.421307 +-0.851014 0.313486 0.421308 +-0.851016 0.313484 0.421307 +-0.978815 -0.106370 0.174947 +-0.978815 -0.106373 0.174946 +-0.846204 -0.528993 -0.064071 +-0.978815 -0.106370 0.174947 +-0.846205 -0.528991 -0.064070 +-0.978815 -0.106370 0.174947 +-0.846204 -0.528993 -0.064071 +-0.978815 -0.106373 0.174946 +-0.488721 -0.841119 -0.231670 +-0.846205 -0.528991 -0.064070 +-0.488732 -0.841113 -0.231667 +-0.846205 -0.528991 -0.064070 +-0.488721 -0.841119 -0.231670 +-0.846204 -0.528993 -0.064071 +-0.002162 -0.959134 -0.282944 +-0.488721 -0.841119 -0.231670 +-0.488732 -0.841113 -0.231667 +-0.002162 -0.959134 -0.282944 +-0.488732 -0.841113 -0.231667 +-0.002160 -0.959134 -0.282944 +-0.002162 -0.959134 -0.282944 +0.483127 -0.851408 -0.204186 +0.483123 -0.851410 -0.204187 +0.483127 -0.851408 -0.204186 +-0.002162 -0.959134 -0.282944 +-0.002160 -0.959134 -0.282944 +0.483123 -0.851410 -0.204187 +0.837094 -0.546811 -0.016471 +0.837093 -0.546813 -0.016472 +0.837094 -0.546811 -0.016471 +0.483123 -0.851410 -0.204187 +0.483127 -0.851408 -0.204186 +0.837093 -0.546813 -0.016472 +0.964897 -0.126949 0.229907 +0.964897 -0.126947 0.229908 +0.964897 -0.126949 0.229907 +0.837093 -0.546813 -0.016472 +0.837094 -0.546811 -0.016471 +0.964897 -0.126947 0.229908 +0.964897 -0.126949 0.229907 +0.832290 0.295664 0.468910 +0.964897 -0.126949 0.229907 +0.832291 0.295663 0.468909 +0.832290 0.295664 0.468910 +0.832290 0.295664 0.468910 +0.832291 0.295663 0.468909 +0.474813 0.607795 0.636504 +0.832291 0.295663 0.468909 +0.474815 0.607794 0.636503 +0.474813 0.607795 0.636504 +0.474813 0.607795 0.636504 +-0.011755 0.725812 0.687793 +-0.011765 0.725812 0.687793 +-0.011755 0.725812 0.687793 +0.474813 0.607795 0.636504 +0.474815 0.607794 0.636503 +-0.497049 0.618083 0.609028 +-0.011765 0.725812 0.687793 +-0.011755 0.725812 0.687793 +-0.497049 0.618083 0.609028 +-0.011755 0.725812 0.687793 +-0.497051 0.618083 0.609028 +0.029766 0.499101 -0.866032 +0.029771 0.499101 -0.866033 +0.029771 0.499101 -0.866032 +0.029771 0.499101 -0.866033 +0.029766 0.499101 -0.866032 +0.029766 0.499101 -0.866032 +-0.029770 -0.499104 0.866030 +-0.029778 -0.499102 0.866031 +-0.029768 -0.499093 0.866037 +0.029771 0.499101 -0.866032 +0.029783 0.499111 -0.866026 +0.029783 0.499111 -0.866026 +0.029783 0.499111 -0.866026 +0.029771 0.499101 -0.866032 +0.029771 0.499101 -0.866033 +-0.029770 -0.499104 0.866030 +-0.029768 -0.499093 0.866037 +-0.029769 -0.499111 0.866027 +0.029780 0.499126 -0.866018 +0.029783 0.499111 -0.866026 +0.029780 0.499126 -0.866018 +0.029783 0.499111 -0.866026 +0.029780 0.499126 -0.866018 +0.029783 0.499111 -0.866026 +-0.029770 -0.499104 0.866030 +-0.029769 -0.499111 0.866027 +-0.029776 -0.499117 0.866023 +0.029780 0.499126 -0.866018 +0.029782 0.499112 -0.866026 +0.029782 0.499112 -0.866026 +0.029780 0.499126 -0.866018 +0.029782 0.499112 -0.866026 +0.029780 0.499126 -0.866018 +-0.029770 -0.499104 0.866030 +-0.029776 -0.499117 0.866023 +-0.029768 -0.499104 0.866031 +0.029776 0.499105 -0.866030 +0.029782 0.499112 -0.866026 +0.029782 0.499112 -0.866026 +0.029776 0.499105 -0.866030 +0.029782 0.499112 -0.866026 +0.029776 0.499105 -0.866030 +-0.029770 -0.499104 0.866030 +-0.029768 -0.499104 0.866031 +-0.029765 -0.499109 0.866028 +0.029776 0.499105 -0.866030 +0.029774 0.499112 -0.866026 +0.029774 0.499112 -0.866026 +0.029774 0.499112 -0.866026 +0.029776 0.499105 -0.866030 +0.029776 0.499105 -0.866030 +-0.029770 -0.499104 0.866030 +-0.029765 -0.499109 0.866028 +-0.029770 -0.499100 0.866033 +0.029783 0.499102 -0.866031 +0.029774 0.499112 -0.866026 +0.029774 0.499112 -0.866026 +0.029774 0.499112 -0.866026 +0.029783 0.499102 -0.866031 +0.029783 0.499102 -0.866031 +-0.029770 -0.499104 0.866030 +-0.029770 -0.499100 0.866033 +-0.029767 -0.499096 0.866035 +0.029767 0.499097 -0.866035 +0.029783 0.499102 -0.866031 +0.029783 0.499102 -0.866031 +0.029783 0.499102 -0.866031 +0.029767 0.499097 -0.866035 +0.029767 0.499097 -0.866035 +-0.029770 -0.499104 0.866030 +-0.029767 -0.499096 0.866035 +-0.029769 -0.499112 0.866026 +0.029754 0.499091 -0.866039 +0.029767 0.499097 -0.866035 +0.029767 0.499097 -0.866035 +0.029754 0.499091 -0.866039 +0.029767 0.499097 -0.866035 +0.029754 0.499091 -0.866039 +-0.029770 -0.499104 0.866030 +-0.029769 -0.499112 0.866026 +-0.029774 -0.499103 0.866031 +0.029764 0.499093 -0.866037 +0.029754 0.499091 -0.866039 +0.029754 0.499091 -0.866039 +0.029764 0.499093 -0.866037 +0.029754 0.499091 -0.866039 +0.029764 0.499093 -0.866037 +-0.029770 -0.499104 0.866030 +-0.029774 -0.499103 0.866031 +-0.029767 -0.499097 0.866035 +0.029772 0.499102 -0.866031 +0.029764 0.499093 -0.866037 +0.029772 0.499102 -0.866031 +0.029764 0.499093 -0.866037 +0.029772 0.499102 -0.866031 +0.029764 0.499093 -0.866037 +-0.029770 -0.499104 0.866030 +-0.029767 -0.499097 0.866035 +-0.029772 -0.499108 0.866028 +0.029766 0.499101 -0.866032 +0.029772 0.499102 -0.866031 +0.029772 0.499102 -0.866031 +0.029772 0.499102 -0.866031 +0.029766 0.499101 -0.866032 +0.029766 0.499101 -0.866032 +-0.029770 -0.499104 0.866030 +-0.029772 -0.499108 0.866028 +-0.029778 -0.499102 0.866031 +-0.465731 0.829022 0.309545 +-0.000122 0.996344 0.085431 +-0.493272 0.866583 0.075610 +-0.000122 0.996344 0.085431 +-0.465731 0.829022 0.309545 +-0.000093 0.938959 0.344030 +-0.859154 0.509571 0.046809 +-0.834222 0.511425 0.206198 +-0.465731 0.829022 0.309545 +-0.465731 0.829022 0.309545 +-0.493272 0.866583 0.075610 +-0.859154 0.509571 0.046809 +-0.997993 0.042079 0.047316 +-0.834222 0.511425 0.206198 +-0.999880 0.014978 0.003858 +-0.834222 0.511425 0.206198 +-0.859154 0.509571 0.046809 +-0.999880 0.014978 0.003858 +-0.882107 -0.452815 -0.129789 +-0.997993 0.042079 0.047316 +-0.871994 -0.487530 -0.044048 +-0.997993 0.042079 0.047316 +-0.999880 0.014978 0.003858 +-0.871994 -0.487530 -0.044048 +-0.505266 -0.858946 -0.083171 +-0.510893 -0.816462 -0.269033 +-0.882107 -0.452815 -0.129789 +-0.882107 -0.452815 -0.129789 +-0.871994 -0.487530 -0.044048 +-0.505266 -0.858946 -0.083171 +0.000217 -0.946296 -0.323302 +-0.510893 -0.816462 -0.269033 +-0.000221 -0.995081 -0.099066 +-0.510893 -0.816462 -0.269033 +-0.505266 -0.858946 -0.083171 +-0.000221 -0.995081 -0.099066 +0.511864 -0.814078 -0.274358 +0.000217 -0.946296 -0.323302 +0.504886 -0.858983 -0.085077 +0.000217 -0.946296 -0.323302 +-0.000221 -0.995081 -0.099066 +0.504886 -0.858983 -0.085077 +0.504886 -0.858983 -0.085077 +0.883607 -0.447758 -0.136936 +0.511864 -0.814078 -0.274358 +0.883607 -0.447758 -0.136936 +0.504886 -0.858983 -0.085077 +0.871876 -0.487481 -0.046852 +0.871876 -0.487481 -0.046852 +0.997960 0.048382 0.041659 +0.883607 -0.447758 -0.136936 +0.997960 0.048382 0.041659 +0.871876 -0.487481 -0.046852 +0.999882 0.015326 0.001306 +0.999882 0.015326 0.001306 +0.832555 0.515556 0.202617 +0.997960 0.048382 0.041659 +0.832555 0.515556 0.202617 +0.999882 0.015326 0.001306 +0.859002 0.509983 0.045092 +0.859002 0.509983 0.045092 +0.464709 0.830270 0.307728 +0.832555 0.515556 0.202617 +0.464709 0.830270 0.307728 +0.859002 0.509983 0.045092 +0.493025 0.866793 0.074803 +-0.000093 0.938959 0.344030 +0.464709 0.830270 0.307728 +-0.000122 0.996344 0.085431 +0.464709 0.830270 0.307728 +0.493025 0.866793 0.074803 +-0.000122 0.996344 0.085431 +-0.493272 0.866583 0.075610 +-0.499223 0.866473 -0.000000 +-0.859154 0.509571 0.046809 +-0.859154 0.509571 0.046809 +-0.499223 0.866473 -0.000000 +-0.865496 0.500917 -0.000000 +-0.999880 0.014978 0.003858 +-0.859154 0.509571 0.046809 +-0.865496 0.500917 -0.000000 +-0.999880 0.014978 0.003858 +-0.865496 0.500917 -0.000000 +-1.000000 0.000286 -0.000000 +-0.999880 0.014978 0.003858 +-0.865676 -0.500605 -0.000000 +-0.871994 -0.487530 -0.044048 +-0.865676 -0.500605 -0.000000 +-0.999880 0.014978 0.003858 +-1.000000 0.000286 -0.000000 +-0.871994 -0.487530 -0.044048 +-0.499229 -0.866470 -0.000000 +-0.505266 -0.858946 -0.083171 +-0.499229 -0.866470 -0.000000 +-0.871994 -0.487530 -0.044048 +-0.865676 -0.500605 -0.000000 +-0.505266 -0.858946 -0.083171 +0.000053 -1.000000 0.000000 +-0.000221 -0.995081 -0.099066 +0.000053 -1.000000 0.000000 +-0.505266 -0.858946 -0.083171 +-0.499229 -0.866470 -0.000000 +0.504886 -0.858983 -0.085077 +-0.000221 -0.995081 -0.099066 +0.000053 -1.000000 0.000000 +0.504886 -0.858983 -0.085077 +0.000053 -1.000000 0.000000 +0.499273 -0.866445 0.000000 +0.504886 -0.858983 -0.085077 +0.499273 -0.866445 0.000000 +0.871876 -0.487481 -0.046852 +0.871876 -0.487481 -0.046852 +0.499273 -0.866445 0.000000 +0.865652 -0.500645 0.000000 +0.999882 0.015326 0.001306 +0.871876 -0.487481 -0.046852 +0.865652 -0.500645 0.000000 +0.999882 0.015326 0.001306 +0.865652 -0.500645 0.000000 +1.000000 0.000216 0.000000 +0.999882 0.015326 0.001306 +0.865507 0.500896 0.000000 +0.859002 0.509983 0.045092 +0.865507 0.500896 0.000000 +0.999882 0.015326 0.001306 +1.000000 0.000216 0.000000 +0.859002 0.509983 0.045092 +0.499205 0.866484 0.000000 +0.493025 0.866793 0.074803 +0.499205 0.866484 0.000000 +0.859002 0.509983 0.045092 +0.865507 0.500896 0.000000 +0.493025 0.866793 0.074803 +-0.000017 1.000000 -0.000000 +-0.000122 0.996344 0.085431 +-0.000017 1.000000 -0.000000 +0.493025 0.866793 0.074803 +0.499205 0.866484 0.000000 +-0.493272 0.866583 0.075610 +-0.000122 0.996344 0.085431 +-0.000017 1.000000 -0.000000 +-0.493272 0.866583 0.075610 +-0.000017 1.000000 -0.000000 +-0.499223 0.866473 -0.000000 +-0.465333 0.817569 0.339185 +-0.834222 0.511425 0.206198 +-0.838301 0.497264 0.223562 +-0.834222 0.511425 0.206198 +-0.465333 0.817569 0.339185 +-0.465731 0.829022 0.309545 +-0.838301 0.497264 0.223562 +-0.997993 0.042079 0.047316 +-0.998673 0.023770 0.045694 +-0.997993 0.042079 0.047316 +-0.838301 0.497264 0.223562 +-0.834222 0.511425 0.206198 +-0.998673 0.023770 0.045694 +-0.882107 -0.452815 -0.129789 +-0.871795 -0.466698 -0.148882 +-0.882107 -0.452815 -0.129789 +-0.998673 0.023770 0.045694 +-0.997993 0.042079 0.047316 +-0.871795 -0.466698 -0.148882 +-0.510893 -0.816462 -0.269033 +-0.495873 -0.816072 -0.296878 +-0.510893 -0.816462 -0.269033 +-0.871795 -0.466698 -0.148882 +-0.882107 -0.452815 -0.129789 +-0.495873 -0.816072 -0.296878 +-0.510893 -0.816462 -0.269033 +0.006673 -0.935910 -0.352177 +0.006673 -0.935910 -0.352177 +-0.510893 -0.816462 -0.269033 +0.000217 -0.946296 -0.323302 +0.006673 -0.935910 -0.352177 +0.511864 -0.814078 -0.274358 +0.506760 -0.808242 -0.299900 +0.511864 -0.814078 -0.274358 +0.006673 -0.935910 -0.352177 +0.000217 -0.946296 -0.323302 +0.883607 -0.447758 -0.136936 +0.876824 -0.455506 -0.153931 +0.511864 -0.814078 -0.274358 +0.506760 -0.808242 -0.299900 +0.511864 -0.814078 -0.274358 +0.876824 -0.455506 -0.153931 +0.997960 0.048382 0.041659 +0.998715 0.031409 0.039780 +0.883607 -0.447758 -0.136936 +0.876824 -0.455506 -0.153931 +0.883607 -0.447758 -0.136936 +0.998715 0.031409 0.039780 +0.832555 0.515556 0.202617 +0.839554 0.497697 0.217820 +0.997960 0.048382 0.041659 +0.998715 0.031409 0.039780 +0.997960 0.048382 0.041659 +0.839554 0.497697 0.217820 +0.464709 0.830270 0.307728 +0.472751 0.814847 0.335455 +0.832555 0.515556 0.202617 +0.839554 0.497697 0.217820 +0.832555 0.515556 0.202617 +0.472751 0.814847 0.335455 +0.472751 0.814847 0.335455 +-0.000093 0.938959 0.344030 +0.005425 0.926247 0.376877 +-0.000093 0.938959 0.344030 +0.472751 0.814847 0.335455 +0.464709 0.830270 0.307728 +0.005425 0.926247 0.376877 +-0.000093 0.938959 0.344030 +-0.465333 0.817569 0.339185 +-0.465333 0.817569 0.339185 +-0.000093 0.938959 0.344030 +-0.465731 0.829022 0.309545 +0.296012 0.474670 0.828894 +0.000000 0.846632 0.532179 +0.178068 0.854083 0.488707 +0.000000 0.846632 0.532179 +0.296012 0.474670 0.828894 +0.000001 0.494914 0.868942 +0.178068 0.854083 0.488707 +0.812272 0.461252 0.357016 +0.791498 0.461618 0.400550 +0.178068 0.854083 0.488707 +0.791498 0.461618 0.400550 +0.296012 0.474670 0.828894 +0.178068 0.854083 0.488707 +0.000000 0.846632 0.532179 +0.000000 0.998929 -0.046264 +0.000000 0.998929 -0.046264 +-0.055235 0.995786 -0.073205 +0.178068 0.854083 0.488707 +-0.055235 0.995786 -0.073205 +-0.069949 0.996075 -0.054231 +0.258845 0.956905 0.131655 +-0.055235 0.995786 -0.073205 +0.258845 0.956905 0.131655 +0.178068 0.854083 0.488707 +-0.292853 0.767784 -0.569864 +0.000000 0.998929 -0.046264 +-0.000000 0.807994 -0.589191 +0.000000 0.998929 -0.046264 +-0.292853 0.767784 -0.569864 +-0.055235 0.995786 -0.073205 +-0.292853 0.767784 -0.569864 +-0.615934 0.727308 -0.302735 +-0.069949 0.996075 -0.054231 +-0.292853 0.767784 -0.569864 +-0.069949 0.996075 -0.054231 +-0.055235 0.995786 -0.073205 +-0.292853 0.767784 -0.569864 +-0.000000 0.541376 -0.840780 +-0.363392 0.523821 -0.770427 +-0.000000 0.541376 -0.840780 +-0.292853 0.767784 -0.569864 +-0.000000 0.807994 -0.589191 +-0.363392 0.523821 -0.770427 +-0.788663 0.467847 -0.398911 +-0.615934 0.727308 -0.302735 +-0.363392 0.523821 -0.770427 +-0.615934 0.727308 -0.302735 +-0.292853 0.767784 -0.569864 +-0.363387 -0.523815 -0.770433 +0.000000 -0.541368 -0.840785 +-0.292853 -0.767778 -0.569872 +0.000000 -0.807989 -0.589197 +-0.292853 -0.767778 -0.569872 +0.000000 -0.541368 -0.840785 +-0.615936 -0.727302 -0.302744 +-0.363387 -0.523815 -0.770433 +-0.292853 -0.767778 -0.569872 +-0.363387 -0.523815 -0.770433 +-0.615936 -0.727302 -0.302744 +-0.788661 -0.467845 -0.398916 +-0.292853 -0.767778 -0.569872 +-0.000000 -0.998929 -0.046266 +-0.055239 -0.995786 -0.073207 +-0.000000 -0.998929 -0.046266 +-0.292853 -0.767778 -0.569872 +0.000000 -0.807989 -0.589197 +-0.292853 -0.767778 -0.569872 +-0.069955 -0.996075 -0.054234 +-0.615936 -0.727302 -0.302744 +-0.069955 -0.996075 -0.054234 +-0.292853 -0.767778 -0.569872 +-0.055239 -0.995786 -0.073207 +-0.055239 -0.995786 -0.073207 +-0.000000 -0.998929 -0.046266 +0.178069 -0.854076 0.488719 +-0.000000 -0.846629 0.532183 +0.178069 -0.854076 0.488719 +-0.000000 -0.998929 -0.046266 +-0.055239 -0.995786 -0.073207 +0.258851 -0.956901 0.131672 +-0.069955 -0.996075 -0.054234 +0.258851 -0.956901 0.131672 +-0.055239 -0.995786 -0.073207 +0.178069 -0.854076 0.488719 +0.178069 -0.854076 0.488719 +-0.000000 -0.846629 0.532183 +0.296011 -0.474665 0.828897 +-0.000000 -0.494906 0.868946 +0.296011 -0.474665 0.828897 +-0.000000 -0.846629 0.532183 +0.791500 -0.461615 0.400549 +0.178069 -0.854076 0.488719 +0.296011 -0.474665 0.828897 +0.178069 -0.854076 0.488719 +0.791500 -0.461615 0.400549 +0.812275 -0.461248 0.357015 +0.291610 0.953477 0.076455 +-0.069949 0.996075 -0.054231 +-0.081099 0.966350 -0.244113 +-0.069949 0.996075 -0.054231 +0.291610 0.953477 0.076455 +0.258845 0.956905 0.131655 +-0.081099 0.966350 -0.244113 +-0.615934 0.727308 -0.302735 +-0.594363 0.726356 -0.345166 +-0.615934 0.727308 -0.302735 +-0.081099 0.966350 -0.244113 +-0.069949 0.996075 -0.054231 +-0.594363 0.726356 -0.345166 +-0.615934 0.727308 -0.302735 +-0.992646 0.000000 -0.121053 +-0.992646 0.000000 -0.121053 +-0.615934 0.727308 -0.302735 +-0.788663 0.467847 -0.398911 +-0.992646 0.000000 -0.121053 +-0.615936 -0.727302 -0.302744 +-0.594367 -0.726352 -0.345169 +-0.615936 -0.727302 -0.302744 +-0.992646 0.000000 -0.121053 +-0.788661 -0.467845 -0.398916 +-0.069955 -0.996075 -0.054234 +-0.081104 -0.966349 -0.244114 +-0.615936 -0.727302 -0.302744 +-0.594367 -0.726352 -0.345169 +-0.615936 -0.727302 -0.302744 +-0.081104 -0.966349 -0.244114 +0.258851 -0.956901 0.131672 +0.291617 -0.953474 0.076464 +-0.069955 -0.996075 -0.054234 +-0.081104 -0.966349 -0.244114 +-0.069955 -0.996075 -0.054234 +0.291617 -0.953474 0.076464 +0.874192 -0.466919 0.133323 +0.791500 -0.461615 0.400549 +0.993375 -0.000000 0.114914 +0.791500 -0.461615 0.400549 +0.874192 -0.466919 0.133323 +0.812275 -0.461248 0.357015 +0.993375 -0.000000 0.114914 +0.791498 0.461618 0.400550 +0.874191 0.466922 0.133318 +0.874191 0.466922 0.133318 +0.791498 0.461618 0.400550 +0.812272 0.461252 0.357016 +0.993375 -0.000000 0.114914 +0.874191 0.466922 0.133318 +0.986237 0.161132 0.037062 +0.189531 0.716921 -0.670897 +-0.081099 0.966350 -0.244113 +-0.039204 0.957012 -0.287388 +-0.911337 0.394183 -0.118680 +-0.039204 0.957012 -0.287388 +-0.081099 0.966350 -0.244113 +-0.911337 0.394183 -0.118680 +-0.081099 0.966350 -0.244113 +-0.594363 0.726356 -0.345166 +-0.594363 0.726356 -0.345166 +-0.992646 0.000000 -0.121053 +-0.911337 0.394183 -0.118680 +-0.992646 0.000000 -0.121053 +-0.594367 -0.726352 -0.345169 +-0.911338 -0.394181 -0.118680 +-0.911338 -0.394181 -0.118680 +-0.081104 -0.966349 -0.244114 +-0.039205 -0.957012 -0.287387 +-0.081104 -0.966349 -0.244114 +-0.911338 -0.394181 -0.118680 +-0.594367 -0.726352 -0.345169 +-0.081104 -0.966349 -0.244114 +0.189543 -0.716919 -0.670895 +-0.039205 -0.957012 -0.287387 +0.874192 -0.466919 0.133323 +0.993375 -0.000000 0.114914 +0.986237 -0.161132 0.037061 +0.004812 0.996985 0.077440 +-0.911337 0.394183 -0.118680 +0.005401 0.996197 0.086966 +-0.911337 0.394183 -0.118680 +0.004812 0.996985 0.077440 +-0.039204 0.957012 -0.287388 +0.004811 -0.996985 0.077444 +0.005401 -0.996196 0.086970 +-0.911338 -0.394181 -0.118680 +0.004811 -0.996985 0.077444 +-0.911338 -0.394181 -0.118680 +-0.039205 -0.957012 -0.287387 +0.065801 -0.000000 0.997833 +0.065801 -0.000000 0.997833 +0.062252 -0.231591 0.970819 +0.065801 -0.000000 0.997833 +0.062387 -0.225720 0.972192 +0.062252 -0.231591 0.970819 +0.062387 0.225718 0.972193 +0.065801 -0.000000 0.997833 +0.062251 0.231589 0.970820 +0.065801 -0.000000 0.997833 +0.062387 0.225718 0.972193 +0.065801 -0.000000 0.997833 +0.035447 0.815817 0.577223 +0.062387 0.225718 0.972193 +0.062251 0.231589 0.970820 +0.062387 0.225718 0.972193 +0.035447 0.815817 0.577223 +0.036542 0.802733 0.595218 +0.036542 0.802733 0.595218 +0.035447 0.815817 0.577223 +0.005401 0.996197 0.086966 +0.035447 0.815817 0.577223 +0.004812 0.996985 0.077440 +0.005401 0.996197 0.086966 +0.036543 -0.802734 0.595217 +0.035448 -0.815817 0.577223 +0.062387 -0.225720 0.972192 +0.062252 -0.231591 0.970819 +0.062387 -0.225720 0.972192 +0.035448 -0.815817 0.577223 +0.035448 -0.815817 0.577223 +0.005401 -0.996196 0.086970 +0.004811 -0.996985 0.077444 +0.005401 -0.996196 0.086970 +0.035448 -0.815817 0.577223 +0.036543 -0.802734 0.595217 +0.999239 -0.000000 0.039012 +0.986237 0.161132 0.037062 +0.986406 0.159747 0.038512 +0.986406 0.159747 0.038512 +0.986406 0.159747 0.038512 +0.986406 0.159747 0.038512 +0.999239 -0.000000 0.039012 +0.986406 0.159747 0.038512 +0.986406 0.159747 0.038512 +0.986237 0.161132 0.037062 +0.999239 -0.000000 0.039012 +0.993375 -0.000000 0.114914 +-0.992646 0.000000 -0.121053 +-0.999744 0.000000 -0.022607 +-0.998756 0.044458 -0.022585 +-0.992646 0.000000 -0.121053 +-0.998756 0.044458 -0.022585 +-0.911337 0.394183 -0.118680 +-0.998756 0.044458 -0.022585 +-0.999744 0.000000 -0.022607 +-0.998756 0.044458 -0.022585 +-0.998756 0.044458 -0.022585 +-0.998756 0.044458 -0.022585 +-0.998756 0.044458 -0.022585 +-0.999744 0.000000 -0.022607 +-0.992646 0.000000 -0.121053 +-0.998756 -0.044458 -0.022585 +-0.998756 -0.044458 -0.022585 +-0.998756 -0.044458 -0.022585 +-0.998756 -0.044458 -0.022585 +-0.999744 0.000000 -0.022607 +-0.998756 -0.044458 -0.022585 +-0.998756 -0.044458 -0.022585 +-0.998756 -0.044458 -0.022585 +-0.992646 0.000000 -0.121053 +-0.911338 -0.394181 -0.118680 +0.999239 -0.000000 0.039012 +0.986237 -0.161132 0.037061 +0.993375 -0.000000 0.114914 +0.986237 -0.161132 0.037061 +0.999239 -0.000000 0.039012 +0.986407 -0.159747 0.038511 +0.986407 -0.159747 0.038511 +0.999239 -0.000000 0.039012 +0.986407 -0.159747 0.038511 +0.986407 -0.159747 0.038511 +0.986407 -0.159747 0.038511 +0.986407 -0.159747 0.038511 +0.000000 0.846632 0.532179 +-0.296010 0.474667 0.828896 +-0.178068 0.854082 0.488709 +-0.296010 0.474667 0.828896 +0.000000 0.846632 0.532179 +0.000001 0.494914 0.868942 +-0.812272 0.461251 0.357018 +-0.178068 0.854082 0.488709 +-0.791496 0.461617 0.400553 +-0.791496 0.461617 0.400553 +-0.178068 0.854082 0.488709 +-0.296010 0.474667 0.828896 +-0.178068 0.854082 0.488709 +0.000000 0.998929 -0.046264 +0.000000 0.846632 0.532179 +0.000000 0.998929 -0.046264 +-0.178068 0.854082 0.488709 +0.055235 0.995786 -0.073205 +0.055235 0.995786 -0.073205 +-0.258844 0.956904 0.131658 +0.069949 0.996075 -0.054229 +-0.178068 0.854082 0.488709 +-0.258844 0.956904 0.131658 +0.055235 0.995786 -0.073205 +0.292854 0.767785 -0.569862 +0.000000 0.998929 -0.046264 +0.055235 0.995786 -0.073205 +0.000000 0.998929 -0.046264 +0.292854 0.767785 -0.569862 +-0.000000 0.807994 -0.589191 +0.292854 0.767785 -0.569862 +0.069949 0.996075 -0.054229 +0.615935 0.727308 -0.302733 +0.055235 0.995786 -0.073205 +0.069949 0.996075 -0.054229 +0.292854 0.767785 -0.569862 +-0.000000 0.541376 -0.840780 +0.292854 0.767785 -0.569862 +0.363394 0.523822 -0.770425 +0.292854 0.767785 -0.569862 +-0.000000 0.541376 -0.840780 +-0.000000 0.807994 -0.589191 +0.788664 0.467847 -0.398908 +0.363394 0.523822 -0.770425 +0.615935 0.727308 -0.302733 +0.615935 0.727308 -0.302733 +0.363394 0.523822 -0.770425 +0.292854 0.767785 -0.569862 +0.292853 -0.767778 -0.569872 +0.000000 -0.807989 -0.589197 +0.000000 -0.541368 -0.840785 +0.292853 -0.767778 -0.569872 +0.000000 -0.541368 -0.840785 +0.363387 -0.523815 -0.770433 +0.363387 -0.523815 -0.770433 +0.615936 -0.727302 -0.302745 +0.292853 -0.767778 -0.569872 +0.615936 -0.727302 -0.302745 +0.363387 -0.523815 -0.770433 +0.788661 -0.467845 -0.398917 +-0.000000 -0.998929 -0.046266 +0.292853 -0.767778 -0.569872 +0.055238 -0.995786 -0.073209 +0.292853 -0.767778 -0.569872 +-0.000000 -0.998929 -0.046266 +0.000000 -0.807989 -0.589197 +0.292853 -0.767778 -0.569872 +0.069955 -0.996075 -0.054235 +0.055238 -0.995786 -0.073209 +0.069955 -0.996075 -0.054235 +0.292853 -0.767778 -0.569872 +0.615936 -0.727302 -0.302745 +-0.000000 -0.998929 -0.046266 +-0.178070 -0.854078 0.488714 +-0.000000 -0.846629 0.532183 +-0.178070 -0.854078 0.488714 +-0.000000 -0.998929 -0.046266 +0.055238 -0.995786 -0.073209 +0.055238 -0.995786 -0.073209 +-0.258851 -0.956901 0.131668 +-0.178070 -0.854078 0.488714 +-0.258851 -0.956901 0.131668 +0.055238 -0.995786 -0.073209 +0.069955 -0.996075 -0.054235 +-0.296012 -0.474666 0.828896 +-0.000000 -0.494906 0.868946 +-0.000000 -0.846629 0.532183 +-0.296012 -0.474666 0.828896 +-0.000000 -0.846629 0.532183 +-0.178070 -0.854078 0.488714 +-0.178070 -0.854078 0.488714 +-0.791501 -0.461615 0.400546 +-0.296012 -0.474666 0.828896 +-0.791501 -0.461615 0.400546 +-0.178070 -0.854078 0.488714 +-0.812276 -0.461249 0.357013 +0.069949 0.996075 -0.054229 +-0.291610 0.953476 0.076460 +0.081099 0.966350 -0.244112 +-0.291610 0.953476 0.076460 +0.069949 0.996075 -0.054229 +-0.258844 0.956904 0.131658 +0.615935 0.727308 -0.302733 +0.081099 0.966350 -0.244112 +0.594363 0.726356 -0.345167 +0.081099 0.966350 -0.244112 +0.615935 0.727308 -0.302733 +0.069949 0.996075 -0.054229 +0.992646 0.000000 -0.121053 +0.615935 0.727308 -0.302733 +0.594363 0.726356 -0.345167 +0.615935 0.727308 -0.302733 +0.992646 0.000000 -0.121053 +0.788664 0.467847 -0.398908 +0.992646 0.000000 -0.121053 +0.615936 -0.727302 -0.302745 +0.788661 -0.467845 -0.398917 +0.615936 -0.727302 -0.302745 +0.992646 0.000000 -0.121053 +0.594366 -0.726351 -0.345170 +0.081104 -0.966349 -0.244116 +0.615936 -0.727302 -0.302745 +0.594366 -0.726351 -0.345170 +0.615936 -0.727302 -0.302745 +0.081104 -0.966349 -0.244116 +0.069955 -0.996075 -0.054235 +-0.291617 -0.953474 0.076464 +0.069955 -0.996075 -0.054235 +0.081104 -0.966349 -0.244116 +0.069955 -0.996075 -0.054235 +-0.291617 -0.953474 0.076464 +-0.258851 -0.956901 0.131668 +-0.874192 -0.466919 0.133322 +-0.791501 -0.461615 0.400546 +-0.812276 -0.461249 0.357013 +-0.791501 -0.461615 0.400546 +-0.874192 -0.466919 0.133322 +-0.993375 0.000000 0.114914 +-0.874191 0.466922 0.133319 +-0.791496 0.461617 0.400553 +-0.993375 0.000000 0.114914 +-0.791496 0.461617 0.400553 +-0.874191 0.466922 0.133319 +-0.812272 0.461251 0.357018 +-0.993375 0.000000 0.114914 +-0.986237 0.161132 0.037062 +-0.874191 0.466922 0.133319 +-0.189531 0.716921 -0.670897 +0.039204 0.957011 -0.287389 +0.081099 0.966350 -0.244112 +0.911337 0.394183 -0.118681 +0.081099 0.966350 -0.244112 +0.039204 0.957011 -0.287389 +0.081099 0.966350 -0.244112 +0.911337 0.394183 -0.118681 +0.594363 0.726356 -0.345167 +0.594363 0.726356 -0.345167 +0.911337 0.394183 -0.118681 +0.992646 0.000000 -0.121053 +0.992646 0.000000 -0.121053 +0.911338 -0.394181 -0.118680 +0.594366 -0.726351 -0.345170 +0.911338 -0.394181 -0.118680 +0.081104 -0.966349 -0.244116 +0.594366 -0.726351 -0.345170 +0.081104 -0.966349 -0.244116 +0.911338 -0.394181 -0.118680 +0.039205 -0.957012 -0.287387 +0.081104 -0.966349 -0.244116 +0.039205 -0.957012 -0.287387 +-0.189542 -0.716919 -0.670895 +-0.874192 -0.466919 0.133322 +-0.986237 -0.161131 0.037061 +-0.993375 0.000000 0.114914 +-0.004812 0.996985 0.077440 +0.911337 0.394183 -0.118681 +0.039204 0.957011 -0.287389 +0.911337 0.394183 -0.118681 +-0.004812 0.996985 0.077440 +-0.005401 0.996197 0.086966 +-0.004811 -0.996985 0.077443 +0.911338 -0.394181 -0.118680 +-0.005401 -0.996196 0.086970 +0.911338 -0.394181 -0.118680 +-0.004811 -0.996985 0.077443 +0.039205 -0.957012 -0.287387 +-0.065801 -0.000000 0.997833 +-0.062252 -0.231590 0.970820 +-0.065801 -0.000000 0.997833 +-0.065801 -0.000000 0.997833 +-0.062252 -0.231590 0.970820 +-0.062387 -0.225719 0.972193 +-0.062387 0.225718 0.972193 +-0.062251 0.231589 0.970820 +-0.065801 -0.000000 0.997833 +-0.062387 0.225718 0.972193 +-0.065801 -0.000000 0.997833 +-0.065801 -0.000000 0.997833 +-0.035447 0.815816 0.577224 +-0.062387 0.225718 0.972193 +-0.036542 0.802732 0.595219 +-0.062387 0.225718 0.972193 +-0.035447 0.815816 0.577224 +-0.062251 0.231589 0.970820 +-0.036542 0.802732 0.595219 +-0.005401 0.996197 0.086966 +-0.035447 0.815816 0.577224 +-0.035447 0.815816 0.577224 +-0.005401 0.996197 0.086966 +-0.004812 0.996985 0.077440 +-0.035447 -0.815817 0.577223 +-0.062387 -0.225719 0.972193 +-0.062252 -0.231590 0.970820 +-0.062387 -0.225719 0.972193 +-0.035447 -0.815817 0.577223 +-0.036543 -0.802734 0.595217 +-0.035447 -0.815817 0.577223 +-0.005401 -0.996196 0.086970 +-0.036543 -0.802734 0.595217 +-0.005401 -0.996196 0.086970 +-0.035447 -0.815817 0.577223 +-0.004811 -0.996985 0.077443 +-0.999239 0.000000 0.039012 +-0.986237 0.161132 0.037062 +-0.993375 0.000000 0.114914 +-0.986406 0.159747 0.038512 +-0.986406 0.159747 0.038512 +-0.986406 0.159747 0.038512 +-0.986406 0.159747 0.038512 +-0.999239 0.000000 0.039012 +-0.986406 0.159747 0.038512 +-0.986237 0.161132 0.037062 +-0.999239 0.000000 0.039012 +-0.986406 0.159747 0.038512 +0.998756 0.044458 -0.022585 +0.999744 0.000000 -0.022607 +0.992646 0.000000 -0.121053 +0.998756 0.044458 -0.022585 +0.992646 0.000000 -0.121053 +0.911337 0.394183 -0.118681 +0.998756 0.044458 -0.022585 +0.998756 0.044458 -0.022585 +0.998756 0.044458 -0.022585 +0.999744 0.000000 -0.022607 +0.998756 0.044458 -0.022585 +0.998756 0.044458 -0.022585 +0.999744 0.000000 -0.022607 +0.998756 -0.044458 -0.022585 +0.992646 0.000000 -0.121053 +0.998756 -0.044458 -0.022585 +0.998756 -0.044458 -0.022585 +0.998756 -0.044458 -0.022585 +0.998756 -0.044458 -0.022585 +0.999744 0.000000 -0.022607 +0.998756 -0.044458 -0.022585 +0.992646 0.000000 -0.121053 +0.998756 -0.044458 -0.022585 +0.911338 -0.394181 -0.118680 +-0.999239 0.000000 0.039012 +-0.986237 -0.161131 0.037061 +-0.986407 -0.159747 0.038511 +-0.986237 -0.161131 0.037061 +-0.999239 0.000000 0.039012 +-0.993375 0.000000 0.114914 +-0.986407 -0.159747 0.038511 +-0.986407 -0.159747 0.038511 +-0.986407 -0.159747 0.038511 +-0.999239 0.000000 0.039012 +-0.986407 -0.159747 0.038511 +-0.986407 -0.159747 0.038511 +0.852815 -0.260699 0.452485 +0.736957 -0.669309 -0.094447 +0.608032 -0.638106 0.472354 +0.736957 -0.669309 -0.094447 +0.852815 -0.260699 0.452485 +0.975373 -0.218398 -0.030819 +0.854269 0.129669 0.503399 +0.975373 -0.218398 -0.030819 +0.852815 -0.260699 0.452485 +0.975373 -0.218398 -0.030819 +0.854269 0.129669 0.503399 +0.974453 0.222388 0.031383 +0.854269 0.129669 0.503399 +0.613144 0.477942 0.628988 +0.742713 0.663040 0.093567 +0.742713 0.663040 0.093567 +0.974453 0.222388 0.031383 +0.854269 0.129669 0.503399 +-0.000001 0.677440 0.735578 +0.742713 0.663040 0.093567 +0.613144 0.477942 0.628988 +0.742713 0.663040 0.093567 +-0.000001 0.677440 0.735578 +-0.000000 0.990190 0.139730 +-0.000001 0.677440 0.735578 +-0.613138 0.477938 0.628997 +-0.742714 0.663040 0.093562 +-0.000001 0.677440 0.735578 +-0.742714 0.663040 0.093562 +-0.000000 0.990190 0.139730 +-0.854268 0.129669 0.503400 +-0.742714 0.663040 0.093562 +-0.613138 0.477938 0.628997 +-0.742714 0.663040 0.093562 +-0.854268 0.129669 0.503400 +-0.974453 0.222388 0.031380 +-0.854268 0.129669 0.503400 +-0.852815 -0.260699 0.452486 +-0.975373 -0.218398 -0.030824 +-0.854268 0.129669 0.503400 +-0.975373 -0.218398 -0.030824 +-0.974453 0.222388 0.031380 +-0.852815 -0.260699 0.452486 +-0.608031 -0.638106 0.472355 +-0.736957 -0.669308 -0.094454 +-0.852815 -0.260699 0.452486 +-0.736957 -0.669308 -0.094454 +-0.975373 -0.218398 -0.030824 +-0.608031 -0.638106 0.472355 +-0.000000 -0.854548 0.519373 +0.000001 -0.990190 -0.139731 +-0.608031 -0.638106 0.472355 +0.000001 -0.990190 -0.139731 +-0.736957 -0.669308 -0.094454 +0.608032 -0.638106 0.472354 +0.000001 -0.990190 -0.139731 +-0.000000 -0.854548 0.519373 +0.000001 -0.990190 -0.139731 +0.608032 -0.638106 0.472354 +0.736957 -0.669309 -0.094447 +0.608032 -0.638106 0.472354 +0.334155 -0.216651 0.917280 +0.852815 -0.260699 0.452485 +0.334155 -0.216651 0.917280 +0.608032 -0.638106 0.472354 +0.186873 -0.332026 0.924574 +0.339723 -0.043590 0.939515 +0.852815 -0.260699 0.452485 +0.334155 -0.216651 0.917280 +0.852815 -0.260699 0.452485 +0.339723 -0.043590 0.939515 +0.854269 0.129669 0.503399 +0.339723 -0.043590 0.939515 +0.187531 0.061767 0.980315 +0.613144 0.477942 0.628988 +0.339723 -0.043590 0.939515 +0.613144 0.477942 0.628988 +0.854269 0.129669 0.503399 +0.187531 0.061767 0.980315 +-0.000001 0.078266 0.996933 +-0.000001 0.677440 0.735578 +-0.000001 0.677440 0.735578 +0.613144 0.477942 0.628988 +0.187531 0.061767 0.980315 +-0.000001 0.677440 0.735578 +-0.187525 0.061765 0.980316 +-0.613138 0.477938 0.628997 +-0.187525 0.061765 0.980316 +-0.000001 0.677440 0.735578 +-0.000001 0.078266 0.996933 +-0.339717 -0.043591 0.939517 +-0.613138 0.477938 0.628997 +-0.187525 0.061765 0.980316 +-0.613138 0.477938 0.628997 +-0.339717 -0.043591 0.939517 +-0.854268 0.129669 0.503400 +-0.339717 -0.043591 0.939517 +-0.334154 -0.216650 0.917280 +-0.852815 -0.260699 0.452486 +-0.339717 -0.043591 0.939517 +-0.852815 -0.260699 0.452486 +-0.854268 0.129669 0.503400 +-0.608031 -0.638106 0.472355 +-0.852815 -0.260699 0.452486 +-0.334154 -0.216650 0.917280 +-0.608031 -0.638106 0.472355 +-0.334154 -0.216650 0.917280 +-0.186876 -0.332029 0.924573 +-0.186876 -0.332029 0.924573 +-0.000000 -0.351098 0.936339 +-0.000000 -0.854548 0.519373 +-0.186876 -0.332029 0.924573 +-0.000000 -0.854548 0.519373 +-0.608031 -0.638106 0.472355 +0.186873 -0.332026 0.924574 +-0.000000 -0.854548 0.519373 +-0.000000 -0.351098 0.936339 +-0.000000 -0.854548 0.519373 +0.186873 -0.332026 0.924574 +0.608032 -0.638106 0.472354 +0.186873 -0.332026 0.924574 +-0.470542 -0.023290 0.882070 +0.334155 -0.216651 0.917280 +-0.470542 -0.023290 0.882070 +0.186873 -0.332026 0.924574 +-0.333656 0.162451 0.928592 +0.334155 -0.216651 0.917280 +-0.469974 -0.224165 0.853741 +0.339723 -0.043590 0.939515 +-0.469974 -0.224165 0.853741 +0.334155 -0.216651 0.917280 +-0.470542 -0.023290 0.882070 +-0.469974 -0.224165 0.853741 +-0.338285 -0.411361 0.846372 +0.187531 0.061767 0.980315 +-0.469974 -0.224165 0.853741 +0.187531 0.061767 0.980315 +0.339723 -0.043590 0.939515 +-0.338285 -0.411361 0.846372 +-0.000001 -0.525446 0.850827 +-0.000001 0.078266 0.996933 +-0.000001 0.078266 0.996933 +0.187531 0.061767 0.980315 +-0.338285 -0.411361 0.846372 +-0.000001 0.078266 0.996933 +0.338285 -0.411360 0.846372 +-0.187525 0.061765 0.980316 +0.338285 -0.411360 0.846372 +-0.000001 0.078266 0.996933 +-0.000001 -0.525446 0.850827 +0.469974 -0.224164 0.853742 +-0.187525 0.061765 0.980316 +0.338285 -0.411360 0.846372 +-0.187525 0.061765 0.980316 +0.469974 -0.224164 0.853742 +-0.339717 -0.043591 0.939517 +0.469974 -0.224164 0.853742 +0.470543 -0.023289 0.882070 +-0.334154 -0.216650 0.917280 +0.469974 -0.224164 0.853742 +-0.334154 -0.216650 0.917280 +-0.339717 -0.043591 0.939517 +-0.186876 -0.332029 0.924573 +-0.334154 -0.216650 0.917280 +0.470543 -0.023289 0.882070 +-0.186876 -0.332029 0.924573 +0.470543 -0.023289 0.882070 +0.333658 0.162453 0.928591 +0.333658 0.162453 0.928591 +-0.000001 0.269462 0.963011 +-0.000000 -0.351098 0.936339 +0.333658 0.162453 0.928591 +-0.000000 -0.351098 0.936339 +-0.186876 -0.332029 0.924573 +-0.333656 0.162451 0.928592 +-0.000000 -0.351098 0.936339 +-0.000001 0.269462 0.963011 +-0.000000 -0.351098 0.936339 +-0.333656 0.162451 0.928592 +0.186873 -0.332026 0.924574 +-0.333656 0.162451 0.928592 +-0.875863 0.144565 0.460397 +-0.470542 -0.023290 0.882070 +-0.875863 0.144565 0.460397 +-0.333656 0.162451 0.928592 +-0.628881 0.530793 0.568126 +-0.876054 -0.268992 0.400216 +-0.470542 -0.023290 0.882070 +-0.875863 0.144565 0.460397 +-0.470542 -0.023290 0.882070 +-0.876054 -0.268992 0.400216 +-0.469974 -0.224165 0.853741 +-0.876054 -0.268992 0.400216 +-0.634100 -0.662877 0.398135 +-0.338285 -0.411361 0.846372 +-0.876054 -0.268992 0.400216 +-0.338285 -0.411361 0.846372 +-0.469974 -0.224165 0.853741 +-0.634100 -0.662877 0.398135 +-0.000000 -0.910916 0.412592 +-0.000001 -0.525446 0.850827 +-0.000001 -0.525446 0.850827 +-0.338285 -0.411361 0.846372 +-0.634100 -0.662877 0.398135 +-0.000001 -0.525446 0.850827 +0.634104 -0.662882 0.398120 +0.338285 -0.411360 0.846372 +0.634104 -0.662882 0.398120 +-0.000001 -0.525446 0.850827 +-0.000000 -0.910916 0.412592 +0.876057 -0.268993 0.400210 +0.338285 -0.411360 0.846372 +0.634104 -0.662882 0.398120 +0.338285 -0.411360 0.846372 +0.876057 -0.268993 0.400210 +0.469974 -0.224164 0.853742 +0.876057 -0.268993 0.400210 +0.470543 -0.023289 0.882070 +0.469974 -0.224164 0.853742 +0.470543 -0.023289 0.882070 +0.876057 -0.268993 0.400210 +0.875865 0.144565 0.460393 +0.333658 0.162453 0.928591 +0.470543 -0.023289 0.882070 +0.875865 0.144565 0.460393 +0.333658 0.162453 0.928591 +0.875865 0.144565 0.460393 +0.628886 0.530796 0.568118 +0.628886 0.530796 0.568118 +-0.000000 0.761166 0.648557 +-0.000001 0.269462 0.963011 +0.628886 0.530796 0.568118 +-0.000001 0.269462 0.963011 +0.333658 0.162453 0.928591 +-0.628881 0.530793 0.568126 +-0.000001 0.269462 0.963011 +-0.000000 0.761166 0.648557 +-0.000001 0.269462 0.963011 +-0.628881 0.530793 0.568126 +-0.333656 0.162451 0.928592 +-0.628881 0.530793 0.568126 +-0.972277 0.231536 0.032677 +-0.875863 0.144565 0.460397 +-0.972277 0.231536 0.032677 +-0.628881 0.530793 0.568126 +-0.713190 0.694094 0.097944 +-0.875863 0.144565 0.460397 +-0.971629 -0.234190 -0.033052 +-0.876054 -0.268992 0.400216 +-0.971629 -0.234190 -0.033052 +-0.875863 0.144565 0.460397 +-0.972277 0.231536 0.032677 +-0.634100 -0.662877 0.398135 +-0.876054 -0.268992 0.400216 +-0.971629 -0.234190 -0.033052 +-0.634100 -0.662877 0.398135 +-0.971629 -0.234190 -0.033052 +-0.718236 -0.688973 -0.097224 +-0.000000 -0.910916 0.412592 +-0.634100 -0.662877 0.398135 +-0.718236 -0.688973 -0.097224 +-0.000000 -0.910916 0.412592 +-0.718236 -0.688973 -0.097224 +-0.000000 -0.990190 -0.139724 +-0.000000 -0.910916 0.412592 +0.718235 -0.688973 -0.097230 +0.634104 -0.662882 0.398120 +0.718235 -0.688973 -0.097230 +-0.000000 -0.910916 0.412592 +-0.000000 -0.990190 -0.139724 +0.634104 -0.662882 0.398120 +0.971629 -0.234190 -0.033053 +0.876057 -0.268993 0.400210 +0.971629 -0.234190 -0.033053 +0.634104 -0.662882 0.398120 +0.718235 -0.688973 -0.097230 +0.971629 -0.234190 -0.033053 +0.875865 0.144565 0.460393 +0.876057 -0.268993 0.400210 +0.875865 0.144565 0.460393 +0.971629 -0.234190 -0.033053 +0.972277 0.231538 0.032669 +0.972277 0.231538 0.032669 +0.628886 0.530796 0.568118 +0.875865 0.144565 0.460393 +0.628886 0.530796 0.568118 +0.972277 0.231538 0.032669 +0.713191 0.694094 0.097942 +0.628886 0.530796 0.568118 +0.000000 0.990191 0.139720 +-0.000000 0.761166 0.648557 +0.000000 0.990191 0.139720 +0.628886 0.530796 0.568118 +0.713191 0.694094 0.097942 +-0.628881 0.530793 0.568126 +-0.000000 0.761166 0.648557 +0.000000 0.990191 0.139720 +-0.628881 0.530793 0.568126 +0.000000 0.990191 0.139720 +-0.713190 0.694094 0.097944 +-0.972277 0.231536 0.032677 +-0.713190 0.694094 0.097944 +-0.628887 0.667284 -0.399040 +-0.972277 0.231536 0.032677 +-0.628887 0.667284 -0.399040 +-0.875864 0.266330 -0.402405 +-0.971629 -0.234190 -0.033052 +-0.972277 0.231536 0.032677 +-0.875864 0.266330 -0.402405 +-0.971629 -0.234190 -0.033052 +-0.875864 0.266330 -0.402405 +-0.876053 -0.147731 -0.459028 +-0.971629 -0.234190 -0.033052 +-0.634097 -0.526812 -0.566030 +-0.718236 -0.688973 -0.097224 +-0.634097 -0.526812 -0.566030 +-0.971629 -0.234190 -0.033052 +-0.876053 -0.147731 -0.459028 +-0.000000 -0.990190 -0.139724 +-0.718236 -0.688973 -0.097224 +-0.634097 -0.526812 -0.566030 +-0.000000 -0.990190 -0.139724 +-0.634097 -0.526812 -0.566030 +0.000000 -0.761165 -0.648558 +-0.000000 -0.990190 -0.139724 +0.634102 -0.526816 -0.566020 +0.718235 -0.688973 -0.097230 +0.634102 -0.526816 -0.566020 +-0.000000 -0.990190 -0.139724 +0.000000 -0.761165 -0.648558 +0.634102 -0.526816 -0.566020 +0.971629 -0.234190 -0.033053 +0.718235 -0.688973 -0.097230 +0.971629 -0.234190 -0.033053 +0.634102 -0.526816 -0.566020 +0.876054 -0.147732 -0.459025 +0.971629 -0.234190 -0.033053 +0.875865 0.266326 -0.402406 +0.972277 0.231538 0.032669 +0.875865 0.266326 -0.402406 +0.971629 -0.234190 -0.033053 +0.876054 -0.147732 -0.459025 +0.972277 0.231538 0.032669 +0.628889 0.667284 -0.399037 +0.713191 0.694094 0.097942 +0.628889 0.667284 -0.399037 +0.972277 0.231538 0.032669 +0.875865 0.266326 -0.402406 +0.713191 0.694094 0.097942 +-0.000000 0.910919 -0.412586 +0.000000 0.990191 0.139720 +-0.000000 0.910919 -0.412586 +0.713191 0.694094 0.097942 +0.628889 0.667284 -0.399037 +-0.713190 0.694094 0.097944 +0.000000 0.990191 0.139720 +-0.000000 0.910919 -0.412586 +-0.713190 0.694094 0.097944 +-0.000000 0.910919 -0.412586 +-0.628887 0.667284 -0.399040 +-0.875864 0.266330 -0.402405 +-0.628887 0.667284 -0.399040 +-0.333660 0.413088 -0.847366 +-0.875864 0.266330 -0.402405 +-0.333660 0.413088 -0.847366 +-0.470544 0.221719 -0.854066 +-0.470544 0.221719 -0.854066 +-0.469975 0.020852 -0.882433 +-0.876053 -0.147731 -0.459028 +-0.876053 -0.147731 -0.459028 +-0.875864 0.266330 -0.402405 +-0.470544 0.221719 -0.854066 +-0.338279 -0.161069 -0.927159 +-0.876053 -0.147731 -0.459028 +-0.469975 0.020852 -0.882433 +-0.876053 -0.147731 -0.459028 +-0.338279 -0.161069 -0.927159 +-0.634097 -0.526812 -0.566030 +-0.634097 -0.526812 -0.566030 +0.000001 -0.269461 -0.963011 +0.000000 -0.761165 -0.648558 +0.000001 -0.269461 -0.963011 +-0.634097 -0.526812 -0.566030 +-0.338279 -0.161069 -0.927159 +0.000001 -0.269461 -0.963011 +0.338281 -0.161070 -0.927158 +0.634102 -0.526816 -0.566020 +0.634102 -0.526816 -0.566020 +0.000000 -0.761165 -0.648558 +0.000001 -0.269461 -0.963011 +0.338281 -0.161070 -0.927158 +0.469973 0.020852 -0.882434 +0.876054 -0.147732 -0.459025 +0.876054 -0.147732 -0.459025 +0.634102 -0.526816 -0.566020 +0.338281 -0.161070 -0.927158 +0.876054 -0.147732 -0.459025 +0.470544 0.221721 -0.854066 +0.875865 0.266326 -0.402406 +0.470544 0.221721 -0.854066 +0.876054 -0.147732 -0.459025 +0.469973 0.020852 -0.882434 +0.875865 0.266326 -0.402406 +0.333664 0.413089 -0.847364 +0.628889 0.667284 -0.399037 +0.333664 0.413089 -0.847364 +0.875865 0.266326 -0.402406 +0.470544 0.221721 -0.854066 +-0.000000 0.525452 -0.850823 +0.628889 0.667284 -0.399037 +0.333664 0.413089 -0.847364 +0.628889 0.667284 -0.399037 +-0.000000 0.525452 -0.850823 +-0.000000 0.910919 -0.412586 +-0.628887 0.667284 -0.399040 +-0.000000 0.525452 -0.850823 +-0.333660 0.413088 -0.847366 +-0.000000 0.525452 -0.850823 +-0.628887 0.667284 -0.399040 +-0.000000 0.910919 -0.412586 +-0.470544 0.221719 -0.854066 +-0.333660 0.413088 -0.847366 +0.186876 -0.063195 -0.980349 +-0.470544 0.221719 -0.854066 +0.186876 -0.063195 -0.980349 +0.334157 0.045656 -0.941411 +0.334157 0.045656 -0.941411 +0.339724 0.218109 -0.914886 +-0.469975 0.020852 -0.882433 +-0.469975 0.020852 -0.882433 +-0.470544 0.221719 -0.854066 +0.334157 0.045656 -0.941411 +0.187529 0.330644 -0.924936 +-0.469975 0.020852 -0.882433 +0.339724 0.218109 -0.914886 +-0.469975 0.020852 -0.882433 +0.187529 0.330644 -0.924936 +-0.338279 -0.161069 -0.927159 +-0.338279 -0.161069 -0.927159 +0.000000 0.351095 -0.936340 +0.000001 -0.269461 -0.963011 +0.000000 0.351095 -0.936340 +-0.338279 -0.161069 -0.927159 +0.187529 0.330644 -0.924936 +0.000000 0.351095 -0.936340 +-0.187527 0.330641 -0.924938 +0.338281 -0.161070 -0.927158 +0.338281 -0.161070 -0.927158 +0.000001 -0.269461 -0.963011 +0.000000 0.351095 -0.936340 +-0.187527 0.330641 -0.924938 +-0.339723 0.218108 -0.914886 +0.469973 0.020852 -0.882434 +0.469973 0.020852 -0.882434 +0.338281 -0.161070 -0.927158 +-0.187527 0.330641 -0.924938 +0.469973 0.020852 -0.882434 +-0.334158 0.045656 -0.941411 +0.470544 0.221721 -0.854066 +-0.334158 0.045656 -0.941411 +0.469973 0.020852 -0.882434 +-0.339723 0.218108 -0.914886 +0.470544 0.221721 -0.854066 +-0.186875 -0.063194 -0.980349 +0.333664 0.413089 -0.847364 +-0.186875 -0.063194 -0.980349 +0.470544 0.221721 -0.854066 +-0.334158 0.045656 -0.941411 +0.000001 -0.078265 -0.996933 +0.333664 0.413089 -0.847364 +-0.186875 -0.063194 -0.980349 +0.333664 0.413089 -0.847364 +0.000001 -0.078265 -0.996933 +-0.000000 0.525452 -0.850823 +-0.333660 0.413088 -0.847366 +0.000001 -0.078265 -0.996933 +0.186876 -0.063195 -0.980349 +0.000001 -0.078265 -0.996933 +-0.333660 0.413088 -0.847366 +-0.000000 0.525452 -0.850823 +0.334157 0.045656 -0.941411 +0.186876 -0.063195 -0.980349 +0.608032 -0.482467 -0.630494 +0.334157 0.045656 -0.941411 +0.608032 -0.482467 -0.630494 +0.852817 -0.125295 -0.506957 +0.339724 0.218109 -0.914886 +0.334157 0.045656 -0.941411 +0.852817 -0.125295 -0.506957 +0.339724 0.218109 -0.914886 +0.852817 -0.125295 -0.506957 +0.854268 0.263920 -0.447854 +0.339724 0.218109 -0.914886 +0.613140 0.633343 -0.472160 +0.187529 0.330644 -0.924936 +0.613140 0.633343 -0.472160 +0.339724 0.218109 -0.914886 +0.854268 0.263920 -0.447854 +0.187529 0.330644 -0.924936 +-0.000000 0.854548 -0.519372 +0.000000 0.351095 -0.936340 +-0.000000 0.854548 -0.519372 +0.187529 0.330644 -0.924936 +0.613140 0.633343 -0.472160 +-0.000000 0.854548 -0.519372 +-0.613137 0.633341 -0.472167 +-0.187527 0.330641 -0.924938 +-0.187527 0.330641 -0.924938 +0.000000 0.351095 -0.936340 +-0.000000 0.854548 -0.519372 +-0.339723 0.218108 -0.914886 +-0.187527 0.330641 -0.924938 +-0.613137 0.633341 -0.472167 +-0.339723 0.218108 -0.914886 +-0.613137 0.633341 -0.472167 +-0.854266 0.263919 -0.447857 +-0.339723 0.218108 -0.914886 +-0.852814 -0.125295 -0.506961 +-0.334158 0.045656 -0.941411 +-0.852814 -0.125295 -0.506961 +-0.339723 0.218108 -0.914886 +-0.854266 0.263919 -0.447857 +-0.334158 0.045656 -0.941411 +-0.608028 -0.482463 -0.630501 +-0.186875 -0.063194 -0.980349 +-0.608028 -0.482463 -0.630501 +-0.334158 0.045656 -0.941411 +-0.852814 -0.125295 -0.506961 +0.000001 -0.677437 -0.735581 +-0.186875 -0.063194 -0.980349 +-0.608028 -0.482463 -0.630501 +-0.186875 -0.063194 -0.980349 +0.000001 -0.677437 -0.735581 +0.000001 -0.078265 -0.996933 +0.186876 -0.063195 -0.980349 +0.000001 -0.677437 -0.735581 +0.608032 -0.482467 -0.630494 +0.000001 -0.677437 -0.735581 +0.186876 -0.063195 -0.980349 +0.000001 -0.078265 -0.996933 +0.736957 -0.669309 -0.094447 +0.975373 -0.218398 -0.030819 +0.852817 -0.125295 -0.506957 +0.852817 -0.125295 -0.506957 +0.608032 -0.482467 -0.630494 +0.736957 -0.669309 -0.094447 +0.975373 -0.218398 -0.030819 +0.974453 0.222388 0.031383 +0.854268 0.263920 -0.447854 +0.854268 0.263920 -0.447854 +0.852817 -0.125295 -0.506957 +0.975373 -0.218398 -0.030819 +0.742713 0.663040 0.093567 +0.854268 0.263920 -0.447854 +0.974453 0.222388 0.031383 +0.854268 0.263920 -0.447854 +0.742713 0.663040 0.093567 +0.613140 0.633343 -0.472160 +-0.000000 0.990190 0.139730 +0.613140 0.633343 -0.472160 +0.742713 0.663040 0.093567 +0.613140 0.633343 -0.472160 +-0.000000 0.990190 0.139730 +-0.000000 0.854548 -0.519372 +-0.000000 0.990190 0.139730 +-0.742714 0.663040 0.093562 +-0.613137 0.633341 -0.472167 +-0.000000 0.990190 0.139730 +-0.613137 0.633341 -0.472167 +-0.000000 0.854548 -0.519372 +-0.742714 0.663040 0.093562 +-0.974453 0.222388 0.031380 +-0.854266 0.263919 -0.447857 +-0.742714 0.663040 0.093562 +-0.854266 0.263919 -0.447857 +-0.613137 0.633341 -0.472167 +-0.975373 -0.218398 -0.030824 +-0.854266 0.263919 -0.447857 +-0.974453 0.222388 0.031380 +-0.854266 0.263919 -0.447857 +-0.975373 -0.218398 -0.030824 +-0.852814 -0.125295 -0.506961 +-0.736957 -0.669308 -0.094454 +-0.852814 -0.125295 -0.506961 +-0.975373 -0.218398 -0.030824 +-0.852814 -0.125295 -0.506961 +-0.736957 -0.669308 -0.094454 +-0.608028 -0.482463 -0.630501 +-0.736957 -0.669308 -0.094454 +0.000001 -0.990190 -0.139731 +0.000001 -0.677437 -0.735581 +-0.736957 -0.669308 -0.094454 +0.000001 -0.677437 -0.735581 +-0.608028 -0.482463 -0.630501 +0.736957 -0.669309 -0.094447 +0.000001 -0.677437 -0.735581 +0.000001 -0.990190 -0.139731 +0.000001 -0.677437 -0.735581 +0.736957 -0.669309 -0.094447 +0.608032 -0.482467 -0.630494 +-0.864227 -0.000001 0.503103 +-0.864224 0.000000 0.503107 +-0.864226 -0.000001 0.503103 +-0.864225 0.000000 0.503105 +-0.864224 0.000000 0.503107 +-0.864227 -0.000001 0.503103 +-0.864225 -0.000002 0.503105 +-0.864226 -0.000001 0.503103 +-0.864225 -0.000002 0.503105 +-0.864226 -0.000001 0.503103 +-0.864225 -0.000002 0.503105 +-0.864227 -0.000001 0.503103 +-0.784613 -0.000000 0.619985 +-0.864226 -0.000001 0.503103 +-0.864224 0.000000 0.503107 +-0.784613 -0.000000 0.619985 +-0.811979 -0.000000 0.583687 +-0.864226 -0.000001 0.503103 +-0.811979 -0.000000 0.583687 +-0.864225 -0.000002 0.503105 +-0.864226 -0.000001 0.503103 +0.864225 -0.000001 0.503105 +0.864225 -0.000000 0.503105 +0.996864 -0.000000 0.079136 +0.864225 -0.000001 0.503105 +0.977160 -0.000000 0.212506 +0.864225 0.000002 0.503105 +0.977160 -0.000000 0.212506 +0.864225 -0.000001 0.503105 +0.996864 -0.000000 0.079136 +0.864224 -0.000000 0.503107 +0.864225 -0.000001 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000001 0.503105 +0.864224 -0.000000 0.503107 +0.864225 -0.000000 0.503105 +0.864225 -0.000000 0.503105 +0.864225 0.000002 0.503105 +0.864225 0.000002 0.503105 +0.864225 0.000002 0.503105 +0.864225 -0.000000 0.503105 +0.864225 -0.000001 0.503105 +0.864225 0.000001 0.503105 +0.864224 -0.000000 0.503107 +0.784351 0.000000 0.620318 +0.809877 0.000000 0.586599 +0.864225 0.000001 0.503105 +0.784351 0.000000 0.620318 +0.864225 0.000001 0.503105 +0.809877 0.000000 0.586599 +0.864225 0.000002 0.503105 +0.864225 0.000001 0.503105 +0.864224 -0.000000 0.503107 +0.864224 -0.000000 0.503107 +0.864224 -0.000000 0.503107 +0.864225 0.000001 0.503105 +0.864225 0.000001 0.503105 +0.864225 0.000002 0.503105 +0.864225 0.000001 0.503105 +0.864225 0.000001 0.503105 +0.864225 0.000001 0.503105 +0.864225 0.000002 0.503105 +0.864225 0.000002 0.503105 +-0.996982 0.000000 0.077639 +-0.864225 0.000001 0.503106 +-0.864224 0.000000 0.503107 +-0.864225 0.000001 0.503106 +-0.980078 0.000001 0.198613 +-0.864225 0.000000 0.503105 +-0.980078 0.000001 0.198613 +-0.864225 0.000001 0.503106 +-0.996982 0.000000 0.077639 +-0.864224 0.000000 0.503107 +-0.864225 0.000001 0.503106 +-0.864225 0.000001 0.503106 +-0.864225 0.000001 0.503106 +-0.864224 0.000000 0.503107 +-0.864224 0.000000 0.503107 +-0.864225 0.000001 0.503106 +-0.864225 0.000000 0.503105 +-0.864225 0.000000 0.503106 +-0.864225 0.000000 0.503105 +-0.864225 0.000001 0.503106 +-0.864225 0.000001 0.503106 +</float_array> + <technique_common> + <accessor source="#MineCartEngine-Normal0-array" count="12270" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="MineCartEngine-UV0"> + <float_array id="MineCartEngine-UV0-array" count="7692"> +0.125422 0.182118 +0.126038 0.192216 +0.117623 0.197807 +0.108556 0.193309 +0.107926 0.183210 +0.116354 0.177613 +0.120798 0.185466 +0.120826 0.189881 +0.117021 0.192133 +0.113177 0.189957 +0.113140 0.185535 +0.116951 0.183289 +0.125422 0.182118 +0.126038 0.192216 +0.120826 0.189881 +0.120798 0.185466 +0.117623 0.197807 +0.117021 0.192133 +0.108556 0.193309 +0.113177 0.189957 +0.107926 0.183210 +0.113140 0.185535 +0.116354 0.177613 +0.116951 0.183289 +0.125422 0.182118 +0.126038 0.192216 +0.120826 0.189881 +0.120798 0.185466 +0.117623 0.197807 +0.117021 0.192133 +0.108556 0.193309 +0.113177 0.189957 +0.107926 0.183210 +0.113140 0.185535 +0.116354 0.177613 +0.116951 0.183289 +0.125422 0.182118 +0.126038 0.192216 +0.120826 0.189882 +0.120798 0.185466 +0.117623 0.197807 +0.117021 0.192133 +0.108556 0.193309 +0.113177 0.189957 +0.107926 0.183210 +0.113140 0.185535 +0.116354 0.177613 +0.116951 0.183289 +0.116358 0.177609 +0.107930 0.183204 +0.112934 0.185956 +0.116474 0.183316 +0.108542 0.193290 +0.113432 0.190349 +0.117600 0.197811 +0.117486 0.192103 +0.126035 0.192223 +0.121036 0.189467 +0.125418 0.182126 +0.120531 0.185072 +0.116358 0.177609 +0.107930 0.183204 +0.112934 0.185956 +0.116474 0.183316 +0.108542 0.193290 +0.113432 0.190349 +0.117600 0.197811 +0.117486 0.192103 +0.126035 0.192223 +0.121036 0.189467 +0.125418 0.182126 +0.120531 0.185072 +0.116358 0.177609 +0.107930 0.183204 +0.112934 0.185956 +0.116474 0.183316 +0.108542 0.193290 +0.113432 0.190349 +0.117600 0.197811 +0.117486 0.192103 +0.126035 0.192223 +0.121036 0.189467 +0.125418 0.182126 +0.120531 0.185073 +0.116358 0.177609 +0.107930 0.183204 +0.112934 0.185956 +0.116474 0.183316 +0.108542 0.193290 +0.113432 0.190349 +0.117600 0.197812 +0.117486 0.192103 +0.126035 0.192223 +0.121036 0.189467 +0.125418 0.182126 +0.120531 0.185072 +0.116358 0.177609 +0.107930 0.183204 +0.112934 0.185956 +0.116474 0.183316 +0.108542 0.193290 +0.113432 0.190349 +0.117600 0.197811 +0.117486 0.192103 +0.126035 0.192223 +0.121036 0.189467 +0.125418 0.182126 +0.120531 0.185072 +0.116358 0.177609 +0.107930 0.183204 +0.112934 0.185956 +0.116474 0.183316 +0.108542 0.193290 +0.113431 0.190349 +0.117600 0.197811 +0.117486 0.192103 +0.126035 0.192223 +0.121036 0.189467 +0.125418 0.182126 +0.120531 0.185072 +0.116358 0.177609 +0.107930 0.183204 +0.112934 0.185956 +0.116474 0.183316 +0.108542 0.193290 +0.113432 0.190349 +0.117600 0.197811 +0.117486 0.192103 +0.126035 0.192223 +0.121036 0.189467 +0.125418 0.182126 +0.120531 0.185072 +0.116358 0.177609 +0.107930 0.183204 +0.112934 0.185956 +0.116474 0.183316 +0.108542 0.193290 +0.113432 0.190349 +0.117600 0.197811 +0.117486 0.192103 +0.126035 0.192223 +0.121036 0.189467 +0.125418 0.182126 +0.120531 0.185072 +0.125422 0.182118 +0.120798 0.185466 +0.120826 0.189881 +0.126038 0.192216 +0.117021 0.192133 +0.117623 0.197807 +0.113177 0.189957 +0.108556 0.193309 +0.113140 0.185535 +0.107926 0.183210 +0.116951 0.183289 +0.116354 0.177613 +0.125422 0.182118 +0.120798 0.185466 +0.120826 0.189882 +0.126038 0.192216 +0.117021 0.192133 +0.117623 0.197807 +0.113177 0.189957 +0.108556 0.193309 +0.113140 0.185535 +0.107926 0.183210 +0.116951 0.183289 +0.116354 0.177613 +0.125422 0.182118 +0.120798 0.185466 +0.120826 0.189881 +0.126038 0.192216 +0.117021 0.192133 +0.117623 0.197807 +0.113177 0.189957 +0.108556 0.193309 +0.113140 0.185535 +0.107926 0.183210 +0.116951 0.183289 +0.116354 0.177613 +0.125422 0.182118 +0.120798 0.185466 +0.120826 0.189882 +0.126038 0.192216 +0.117021 0.192133 +0.117623 0.197807 +0.113177 0.189957 +0.108556 0.193309 +0.113140 0.185535 +0.107926 0.183210 +0.116951 0.183289 +0.116354 0.177613 +0.112055 0.269961 +0.111756 0.259214 +0.122502 0.258916 +0.122801 0.269662 +0.111457 0.248468 +0.122203 0.248169 +0.111159 0.237722 +0.121905 0.237423 +0.112951 0.302199 +0.112652 0.291453 +0.123398 0.291154 +0.123697 0.301901 +0.112354 0.280707 +0.123100 0.280408 +0.139315 0.267827 +0.149499 0.271269 +0.141426 0.278368 +0.151611 0.281810 +0.143537 0.288909 +0.133353 0.285467 +0.131242 0.274926 +0.112055 0.269961 +0.111756 0.259214 +0.122502 0.258916 +0.122801 0.269662 +0.111457 0.248468 +0.122203 0.248169 +0.111159 0.237722 +0.121905 0.237423 +0.112951 0.302199 +0.112652 0.291453 +0.123398 0.291154 +0.123697 0.301901 +0.112354 0.280707 +0.123100 0.280408 +0.139315 0.267827 +0.149499 0.271269 +0.141426 0.278368 +0.151611 0.281810 +0.143537 0.288909 +0.133353 0.285467 +0.131242 0.274926 +0.112652 0.291453 +0.123398 0.291154 +0.123697 0.301901 +0.112951 0.302199 +0.111159 0.237722 +0.121905 0.237423 +0.122203 0.248169 +0.111457 0.248468 +0.122502 0.258916 +0.111756 0.259214 +0.122801 0.269662 +0.112055 0.269961 +0.123100 0.280408 +0.112354 0.280707 +0.131242 0.274926 +0.141426 0.278368 +0.133353 0.285467 +0.143537 0.288909 +0.151611 0.281810 +0.149499 0.271269 +0.139315 0.267827 +0.112652 0.291453 +0.123398 0.291154 +0.123697 0.301901 +0.112951 0.302199 +0.111159 0.237722 +0.121905 0.237423 +0.122203 0.248169 +0.111457 0.248468 +0.122502 0.258916 +0.111756 0.259214 +0.122801 0.269662 +0.112055 0.269961 +0.123100 0.280408 +0.112354 0.280707 +0.131242 0.274926 +0.141426 0.278368 +0.133353 0.285467 +0.143537 0.288909 +0.151611 0.281810 +0.149499 0.271269 +0.139315 0.267827 +0.869831 0.009659 +0.874132 0.009659 +0.874132 0.038448 +0.869831 0.038448 +0.000500 0.854701 +0.003633 0.851567 +0.007934 0.855814 +0.004800 0.858948 +0.427815 0.860870 +0.427814 0.865302 +0.399025 0.865298 +0.399025 0.860867 +0.326232 0.602370 +0.326232 0.606802 +0.297443 0.606805 +0.297442 0.602373 +0.184527 0.671292 +0.187661 0.674426 +0.183360 0.678672 +0.180227 0.675539 +0.004800 0.879324 +0.000500 0.879324 +0.180227 0.650916 +0.184527 0.650916 +0.297440 0.581997 +0.326229 0.581994 +0.028992 0.831656 +0.028992 0.762921 +0.033292 0.762921 +0.033292 0.835902 +0.399037 0.757840 +0.427827 0.757843 +0.427819 0.826578 +0.399029 0.826574 +0.213019 0.694337 +0.213019 0.767318 +0.208719 0.767318 +0.208719 0.698584 +0.326236 0.641094 +0.326244 0.714076 +0.297454 0.714079 +0.297446 0.641097 +0.198924 0.678918 +0.194624 0.683165 +0.326233 0.618928 +0.297444 0.618931 +0.014897 0.847075 +0.019197 0.851322 +0.399027 0.848740 +0.427816 0.848744 +0.029133 0.845943 +0.024833 0.841696 +0.326235 0.630226 +0.297445 0.630230 +0.427818 0.837445 +0.399028 0.837442 +0.208860 0.684297 +0.204560 0.688544 +0.516238 0.941195 +0.516238 0.912406 +0.520538 0.912406 +0.520538 0.941195 +0.000500 0.671141 +0.004800 0.666894 +0.007934 0.670028 +0.003633 0.674275 +0.427839 0.654816 +0.399049 0.654813 +0.399050 0.650381 +0.427839 0.650384 +0.326256 0.825781 +0.297467 0.825785 +0.297466 0.821353 +0.326256 0.821349 +0.184527 0.863345 +0.180227 0.859098 +0.183360 0.855964 +0.187661 0.860211 +0.000500 0.646518 +0.004800 0.646518 +0.180227 0.883721 +0.184527 0.883721 +0.326259 0.846157 +0.297469 0.846161 +0.028992 0.694186 +0.033292 0.689939 +0.399045 0.689105 +0.427835 0.689108 +0.213019 0.840300 +0.208719 0.836053 +0.326252 0.787057 +0.297462 0.787060 +0.194624 0.851472 +0.198924 0.855719 +0.297465 0.809226 +0.326254 0.809223 +0.019197 0.674520 +0.014897 0.678767 +0.427837 0.666942 +0.399048 0.666939 +0.024833 0.684146 +0.029133 0.679899 +0.297464 0.797928 +0.326253 0.797925 +0.399047 0.678237 +0.427836 0.678241 +0.204560 0.846093 +0.208860 0.850340 +0.733444 0.361232 +0.733426 0.343257 +0.741359 0.343249 +0.741377 0.361225 +0.733407 0.325282 +0.741341 0.325274 +0.733389 0.307307 +0.741323 0.307299 +0.733371 0.289332 +0.741304 0.289324 +0.733353 0.271356 +0.741286 0.271348 +0.733335 0.253381 +0.741268 0.253373 +0.733317 0.235406 +0.741250 0.235398 +0.733299 0.217431 +0.741232 0.217423 +0.733281 0.199455 +0.741214 0.199448 +0.733263 0.181480 +0.741196 0.181472 +0.733245 0.163505 +0.741178 0.163497 +0.733227 0.145530 +0.741160 0.145522 +0.733209 0.127555 +0.741142 0.127547 +0.733191 0.109580 +0.741124 0.109572 +0.733173 0.091604 +0.741106 0.091596 +0.733155 0.073629 +0.741088 0.073621 +0.733137 0.055654 +0.741070 0.055646 +0.733119 0.037679 +0.741052 0.037671 +0.733101 0.019704 +0.741033 0.019696 +0.733083 0.001729 +0.741016 0.001721 +0.068272 0.787190 +0.053731 0.776622 +0.058819 0.771536 +0.071538 0.780781 +0.043168 0.762078 +0.049578 0.758813 +0.037617 0.744981 +0.044722 0.743857 +0.037620 0.727006 +0.044725 0.728132 +0.043178 0.709911 +0.049587 0.713178 +0.053747 0.695371 +0.058832 0.700459 +0.068291 0.684808 +0.071555 0.691218 +0.085387 0.679257 +0.086511 0.686362 +0.103362 0.679260 +0.102236 0.686365 +0.120457 0.684818 +0.117190 0.691227 +0.134997 0.695387 +0.129909 0.700472 +0.145560 0.709931 +0.139150 0.713195 +0.151111 0.727027 +0.144006 0.728151 +0.151108 0.745002 +0.144003 0.743876 +0.145550 0.762097 +0.139141 0.758830 +0.134982 0.776637 +0.129896 0.771549 +0.120437 0.787200 +0.117173 0.780790 +0.103341 0.792751 +0.102217 0.785646 +0.085366 0.792748 +0.086492 0.785643 +0.773658 0.125347 +0.761047 0.125367 +0.761017 0.109934 +0.773626 0.109921 +0.773669 0.140778 +0.761059 0.140798 +0.773700 0.156211 +0.761091 0.156224 +0.773702 0.171644 +0.761093 0.171649 +0.773700 0.187075 +0.761091 0.187077 +0.773697 0.202505 +0.761087 0.202506 +0.773694 0.217935 +0.761084 0.217936 +0.773690 0.233364 +0.761080 0.233365 +0.773688 0.248794 +0.761076 0.248795 +0.773687 0.264221 +0.761071 0.264226 +0.773693 0.279645 +0.761064 0.279657 +0.773709 0.295056 +0.761061 0.295082 +0.773643 0.310455 +0.761167 0.310427 +0.761064 0.001979 +0.773539 0.002007 +0.773646 0.017352 +0.760997 0.017378 +0.773643 0.032777 +0.761013 0.032789 +0.773635 0.048208 +0.761019 0.048213 +0.773630 0.063638 +0.761019 0.063641 +0.773626 0.079068 +0.761016 0.079070 +0.773624 0.094496 +0.761014 0.094501 +0.754614 0.295140 +0.754632 0.279664 +0.754645 0.264224 +0.754651 0.248791 +0.754655 0.233361 +0.754659 0.217931 +0.754662 0.202502 +0.754666 0.187073 +0.754668 0.171646 +0.754667 0.156223 +0.754672 0.140807 +0.754587 0.125381 +0.754590 0.109937 +0.754589 0.094499 +0.754591 0.079066 +0.754594 0.063636 +0.754593 0.048207 +0.754586 0.032774 +0.754572 0.017313 +0.754690 0.001700 +0.754763 0.310748 +0.780130 0.140764 +0.780045 0.125338 +0.780127 0.156208 +0.780127 0.171647 +0.780125 0.187079 +0.780122 0.202510 +0.780119 0.217939 +0.780115 0.233369 +0.780113 0.248798 +0.780113 0.264227 +0.780121 0.279660 +0.780135 0.295121 +0.780016 0.310734 +0.779943 0.001686 +0.780093 0.017294 +0.780074 0.032770 +0.780062 0.048210 +0.780055 0.063642 +0.780051 0.079072 +0.780049 0.094499 +0.780050 0.109922 +0.460261 0.739685 +0.449097 0.731572 +0.449781 0.730888 +0.460701 0.738823 +0.440986 0.720405 +0.441847 0.719966 +0.436722 0.707278 +0.437677 0.707127 +0.436723 0.693476 +0.437678 0.693628 +0.440989 0.680351 +0.441851 0.680790 +0.449102 0.669186 +0.449786 0.669870 +0.460269 0.661074 +0.460708 0.661936 +0.473395 0.656811 +0.473547 0.657766 +0.487197 0.656812 +0.487046 0.657767 +0.500323 0.661078 +0.499883 0.661940 +0.511488 0.669191 +0.510804 0.669875 +0.519599 0.680358 +0.518737 0.680797 +0.523863 0.693484 +0.522907 0.693635 +0.523861 0.707286 +0.522906 0.707134 +0.519595 0.720411 +0.518734 0.719972 +0.511482 0.731576 +0.510798 0.730892 +0.500316 0.739688 +0.499876 0.738826 +0.487189 0.743952 +0.487038 0.742996 +0.473387 0.743951 +0.473538 0.742995 +0.444489 0.736186 +0.435178 0.723369 +0.430282 0.708303 +0.430282 0.692461 +0.435177 0.677395 +0.444488 0.664578 +0.457304 0.655266 +0.472370 0.650371 +0.488212 0.650370 +0.503279 0.655266 +0.516095 0.664577 +0.525407 0.677393 +0.530302 0.692459 +0.530303 0.708301 +0.525408 0.723367 +0.516097 0.736184 +0.503281 0.745496 +0.488214 0.750391 +0.472372 0.750392 +0.457305 0.745498 +0.480292 0.700381 +0.733444 0.361232 +0.741377 0.361225 +0.741359 0.343249 +0.733426 0.343257 +0.741341 0.325274 +0.733407 0.325282 +0.741323 0.307299 +0.733389 0.307307 +0.741304 0.289324 +0.733371 0.289332 +0.741286 0.271348 +0.733353 0.271356 +0.741268 0.253373 +0.733335 0.253381 +0.741250 0.235398 +0.733317 0.235406 +0.741232 0.217423 +0.733299 0.217431 +0.741214 0.199448 +0.733281 0.199455 +0.741196 0.181472 +0.733263 0.181480 +0.741178 0.163497 +0.733245 0.163505 +0.741160 0.145522 +0.733227 0.145530 +0.741142 0.127547 +0.733209 0.127555 +0.741124 0.109572 +0.733191 0.109580 +0.741106 0.091596 +0.733173 0.091604 +0.741088 0.073621 +0.733155 0.073629 +0.741070 0.055646 +0.733137 0.055654 +0.741052 0.037671 +0.733119 0.037679 +0.741033 0.019696 +0.733101 0.019704 +0.741016 0.001721 +0.733083 0.001729 +0.068272 0.787190 +0.071538 0.780781 +0.058819 0.771536 +0.053731 0.776622 +0.049578 0.758813 +0.043168 0.762078 +0.044722 0.743857 +0.037617 0.744981 +0.044725 0.728132 +0.037620 0.727006 +0.049587 0.713178 +0.043178 0.709911 +0.058832 0.700459 +0.053747 0.695371 +0.071555 0.691218 +0.068291 0.684808 +0.086511 0.686362 +0.085387 0.679257 +0.102236 0.686365 +0.103362 0.679260 +0.117190 0.691227 +0.120457 0.684818 +0.129909 0.700472 +0.134997 0.695387 +0.139150 0.713195 +0.145560 0.709931 +0.144006 0.728151 +0.151111 0.727027 +0.144003 0.743876 +0.151108 0.745002 +0.139141 0.758830 +0.145550 0.762097 +0.129896 0.771549 +0.134982 0.776637 +0.117173 0.780790 +0.120437 0.787200 +0.102217 0.785646 +0.103341 0.792751 +0.086492 0.785643 +0.085366 0.792748 +0.773658 0.125347 +0.773626 0.109921 +0.761017 0.109934 +0.761047 0.125367 +0.761059 0.140798 +0.773669 0.140778 +0.761091 0.156224 +0.773700 0.156211 +0.761093 0.171649 +0.773702 0.171644 +0.761091 0.187077 +0.773700 0.187075 +0.761087 0.202506 +0.773697 0.202505 +0.761084 0.217936 +0.773694 0.217935 +0.761080 0.233365 +0.773690 0.233364 +0.761076 0.248795 +0.773688 0.248794 +0.761071 0.264226 +0.773687 0.264221 +0.761064 0.279657 +0.773693 0.279645 +0.761061 0.295082 +0.773709 0.295056 +0.761167 0.310427 +0.773643 0.310455 +0.761064 0.001979 +0.760997 0.017378 +0.773646 0.017352 +0.773539 0.002007 +0.761013 0.032789 +0.773643 0.032777 +0.761019 0.048213 +0.773635 0.048208 +0.761019 0.063641 +0.773630 0.063638 +0.761016 0.079070 +0.773626 0.079068 +0.761014 0.094501 +0.773624 0.094496 +0.754614 0.295140 +0.754632 0.279664 +0.754645 0.264224 +0.754651 0.248791 +0.754655 0.233361 +0.754659 0.217931 +0.754662 0.202502 +0.754666 0.187073 +0.754668 0.171646 +0.754667 0.156223 +0.754672 0.140807 +0.754587 0.125381 +0.754590 0.109937 +0.754589 0.094499 +0.754591 0.079066 +0.754594 0.063636 +0.754593 0.048207 +0.754586 0.032774 +0.754572 0.017313 +0.754690 0.001700 +0.754763 0.310748 +0.780130 0.140764 +0.780045 0.125338 +0.780127 0.156208 +0.780127 0.171647 +0.780125 0.187079 +0.780122 0.202510 +0.780119 0.217939 +0.780115 0.233369 +0.780113 0.248798 +0.780113 0.264227 +0.780121 0.279660 +0.780135 0.295121 +0.780016 0.310734 +0.780093 0.017294 +0.779943 0.001686 +0.780074 0.032770 +0.780062 0.048210 +0.780055 0.063642 +0.780051 0.079072 +0.780049 0.094499 +0.780050 0.109922 +0.460261 0.739685 +0.460701 0.738823 +0.449781 0.730888 +0.449097 0.731572 +0.441847 0.719966 +0.440986 0.720405 +0.437677 0.707127 +0.436722 0.707278 +0.437678 0.693628 +0.436723 0.693476 +0.441851 0.680790 +0.440989 0.680351 +0.449786 0.669870 +0.449102 0.669186 +0.460708 0.661936 +0.460269 0.661074 +0.473547 0.657766 +0.473395 0.656811 +0.487046 0.657767 +0.487197 0.656812 +0.499883 0.661940 +0.500323 0.661078 +0.510804 0.669875 +0.511488 0.669191 +0.518737 0.680797 +0.519599 0.680358 +0.522907 0.693635 +0.523863 0.693484 +0.522906 0.707134 +0.523861 0.707286 +0.518734 0.719972 +0.519595 0.720411 +0.510798 0.730892 +0.511482 0.731576 +0.499876 0.738826 +0.500316 0.739688 +0.487038 0.742996 +0.487189 0.743952 +0.473538 0.742995 +0.473387 0.743951 +0.444489 0.736186 +0.435178 0.723369 +0.430282 0.708303 +0.430282 0.692461 +0.435177 0.677395 +0.444488 0.664578 +0.457304 0.655266 +0.472370 0.650371 +0.488212 0.650370 +0.503279 0.655266 +0.516095 0.664577 +0.525407 0.677393 +0.530302 0.692459 +0.530303 0.708301 +0.525408 0.723367 +0.516097 0.736184 +0.503281 0.745496 +0.488214 0.750391 +0.472372 0.750392 +0.457305 0.745498 +0.480292 0.700381 +0.733444 0.361232 +0.741377 0.361225 +0.741359 0.343249 +0.733426 0.343257 +0.741341 0.325274 +0.733407 0.325282 +0.741323 0.307299 +0.733389 0.307307 +0.741304 0.289324 +0.733371 0.289332 +0.741286 0.271348 +0.733353 0.271356 +0.741268 0.253373 +0.733335 0.253381 +0.741250 0.235398 +0.733317 0.235406 +0.741232 0.217423 +0.733299 0.217431 +0.741214 0.199448 +0.733281 0.199455 +0.741196 0.181472 +0.733263 0.181480 +0.741178 0.163497 +0.733245 0.163505 +0.741160 0.145522 +0.733227 0.145530 +0.741142 0.127547 +0.733209 0.127555 +0.741124 0.109572 +0.733191 0.109580 +0.741106 0.091596 +0.733173 0.091604 +0.741088 0.073621 +0.733155 0.073629 +0.741070 0.055646 +0.733137 0.055654 +0.741052 0.037671 +0.733119 0.037679 +0.741033 0.019696 +0.733101 0.019704 +0.741016 0.001721 +0.733083 0.001729 +0.068272 0.787190 +0.071538 0.780781 +0.058819 0.771536 +0.053731 0.776622 +0.049578 0.758813 +0.043168 0.762078 +0.044722 0.743857 +0.037617 0.744981 +0.044725 0.728132 +0.037620 0.727006 +0.049587 0.713178 +0.043178 0.709911 +0.058832 0.700459 +0.053747 0.695371 +0.071555 0.691218 +0.068291 0.684808 +0.086511 0.686362 +0.085387 0.679257 +0.102236 0.686365 +0.103362 0.679260 +0.117190 0.691227 +0.120457 0.684818 +0.129909 0.700472 +0.134997 0.695387 +0.139150 0.713195 +0.145560 0.709931 +0.144006 0.728151 +0.151111 0.727027 +0.144003 0.743876 +0.151108 0.745002 +0.139141 0.758830 +0.145550 0.762097 +0.129896 0.771549 +0.134982 0.776637 +0.117173 0.780790 +0.120437 0.787200 +0.102217 0.785646 +0.103341 0.792751 +0.086492 0.785643 +0.085366 0.792748 +0.773658 0.125347 +0.773626 0.109921 +0.761017 0.109934 +0.761047 0.125367 +0.761059 0.140798 +0.773669 0.140778 +0.761091 0.156224 +0.773700 0.156211 +0.761093 0.171649 +0.773702 0.171644 +0.761091 0.187077 +0.773700 0.187075 +0.761087 0.202506 +0.773697 0.202505 +0.761084 0.217936 +0.773694 0.217935 +0.761080 0.233365 +0.773690 0.233364 +0.761076 0.248795 +0.773688 0.248794 +0.761071 0.264226 +0.773687 0.264221 +0.761064 0.279657 +0.773693 0.279645 +0.761061 0.295082 +0.773709 0.295056 +0.761167 0.310427 +0.773643 0.310455 +0.761064 0.001979 +0.760997 0.017378 +0.773646 0.017352 +0.773539 0.002007 +0.761013 0.032789 +0.773643 0.032777 +0.761019 0.048213 +0.773635 0.048208 +0.761019 0.063641 +0.773630 0.063638 +0.761016 0.079070 +0.773626 0.079068 +0.761014 0.094501 +0.773624 0.094496 +0.754614 0.295140 +0.754632 0.279664 +0.754645 0.264224 +0.754651 0.248791 +0.754655 0.233361 +0.754659 0.217931 +0.754662 0.202502 +0.754666 0.187073 +0.754668 0.171646 +0.754667 0.156223 +0.754672 0.140807 +0.754587 0.125381 +0.754590 0.109937 +0.754589 0.094499 +0.754591 0.079066 +0.754594 0.063636 +0.754593 0.048207 +0.754586 0.032774 +0.754572 0.017313 +0.754690 0.001700 +0.754763 0.310748 +0.780130 0.140764 +0.780045 0.125338 +0.780127 0.156208 +0.780127 0.171647 +0.780125 0.187079 +0.780122 0.202510 +0.780119 0.217939 +0.780115 0.233369 +0.780113 0.248798 +0.780113 0.264227 +0.780121 0.279660 +0.780135 0.295121 +0.780016 0.310734 +0.780093 0.017294 +0.779943 0.001686 +0.780074 0.032770 +0.780062 0.048210 +0.780055 0.063642 +0.780051 0.079072 +0.780049 0.094499 +0.780050 0.109922 +0.460261 0.739685 +0.460701 0.738823 +0.449781 0.730888 +0.449097 0.731572 +0.441847 0.719966 +0.440986 0.720405 +0.437677 0.707127 +0.436722 0.707278 +0.437678 0.693628 +0.436723 0.693476 +0.441851 0.680790 +0.440989 0.680351 +0.449786 0.669870 +0.449102 0.669186 +0.460708 0.661936 +0.460269 0.661074 +0.473547 0.657766 +0.473395 0.656811 +0.487046 0.657767 +0.487197 0.656812 +0.499883 0.661940 +0.500323 0.661078 +0.510804 0.669875 +0.511488 0.669191 +0.518737 0.680797 +0.519599 0.680358 +0.522907 0.693635 +0.523863 0.693484 +0.522906 0.707134 +0.523861 0.707286 +0.518734 0.719972 +0.519595 0.720411 +0.510798 0.730892 +0.511482 0.731576 +0.499876 0.738826 +0.500316 0.739688 +0.487038 0.742996 +0.487189 0.743952 +0.473538 0.742995 +0.473387 0.743951 +0.444489 0.736186 +0.435178 0.723369 +0.430282 0.708303 +0.430282 0.692461 +0.435177 0.677395 +0.444488 0.664578 +0.457304 0.655266 +0.472370 0.650371 +0.488212 0.650370 +0.503279 0.655266 +0.516095 0.664577 +0.525407 0.677393 +0.530302 0.692459 +0.530303 0.708301 +0.525408 0.723367 +0.516097 0.736184 +0.503281 0.745496 +0.488214 0.750391 +0.472372 0.750392 +0.457305 0.745498 +0.480292 0.700381 +0.733444 0.361232 +0.733426 0.343257 +0.741359 0.343249 +0.741377 0.361225 +0.733407 0.325282 +0.741341 0.325274 +0.733389 0.307307 +0.741323 0.307299 +0.733371 0.289332 +0.741304 0.289324 +0.733353 0.271356 +0.741286 0.271348 +0.733335 0.253381 +0.741268 0.253373 +0.733317 0.235406 +0.741250 0.235398 +0.733299 0.217431 +0.741232 0.217423 +0.733281 0.199455 +0.741214 0.199448 +0.733263 0.181480 +0.741196 0.181472 +0.733245 0.163505 +0.741178 0.163497 +0.733227 0.145530 +0.741160 0.145522 +0.733209 0.127555 +0.741142 0.127547 +0.733191 0.109580 +0.741124 0.109572 +0.733173 0.091604 +0.741106 0.091596 +0.733155 0.073629 +0.741088 0.073621 +0.733137 0.055654 +0.741070 0.055646 +0.733119 0.037679 +0.741052 0.037671 +0.733101 0.019704 +0.741033 0.019696 +0.733083 0.001729 +0.741016 0.001721 +0.068272 0.787190 +0.053731 0.776622 +0.058819 0.771536 +0.071538 0.780781 +0.043168 0.762078 +0.049578 0.758813 +0.037617 0.744981 +0.044722 0.743857 +0.037620 0.727006 +0.044725 0.728132 +0.043178 0.709911 +0.049587 0.713178 +0.053747 0.695371 +0.058832 0.700459 +0.068291 0.684808 +0.071555 0.691218 +0.085387 0.679257 +0.086511 0.686362 +0.103362 0.679260 +0.102236 0.686365 +0.120457 0.684818 +0.117190 0.691227 +0.134997 0.695387 +0.129909 0.700472 +0.145560 0.709931 +0.139150 0.713195 +0.151111 0.727027 +0.144006 0.728151 +0.151108 0.745002 +0.144003 0.743876 +0.145550 0.762097 +0.139141 0.758830 +0.134982 0.776637 +0.129896 0.771549 +0.120437 0.787200 +0.117173 0.780790 +0.103341 0.792751 +0.102217 0.785646 +0.085366 0.792748 +0.086492 0.785643 +0.773658 0.125347 +0.761047 0.125367 +0.761017 0.109934 +0.773626 0.109921 +0.773669 0.140778 +0.761059 0.140798 +0.773700 0.156211 +0.761091 0.156224 +0.773702 0.171644 +0.761093 0.171649 +0.773700 0.187075 +0.761091 0.187077 +0.773697 0.202505 +0.761087 0.202506 +0.773694 0.217935 +0.761084 0.217936 +0.773690 0.233364 +0.761080 0.233365 +0.773688 0.248794 +0.761076 0.248795 +0.773687 0.264221 +0.761071 0.264226 +0.773693 0.279645 +0.761064 0.279657 +0.773709 0.295056 +0.761061 0.295082 +0.773643 0.310455 +0.761167 0.310427 +0.761064 0.001979 +0.773539 0.002007 +0.773646 0.017352 +0.760997 0.017378 +0.773643 0.032777 +0.761013 0.032789 +0.773635 0.048208 +0.761019 0.048213 +0.773630 0.063638 +0.761019 0.063641 +0.773626 0.079068 +0.761016 0.079070 +0.773624 0.094496 +0.761014 0.094501 +0.754614 0.295140 +0.754632 0.279664 +0.754645 0.264224 +0.754651 0.248791 +0.754655 0.233361 +0.754659 0.217931 +0.754662 0.202502 +0.754666 0.187073 +0.754668 0.171646 +0.754667 0.156223 +0.754672 0.140807 +0.754587 0.125381 +0.754590 0.109937 +0.754589 0.094499 +0.754591 0.079066 +0.754594 0.063636 +0.754593 0.048207 +0.754586 0.032774 +0.754572 0.017313 +0.754690 0.001700 +0.754763 0.310748 +0.780130 0.140764 +0.780045 0.125338 +0.780127 0.156208 +0.780127 0.171647 +0.780125 0.187079 +0.780122 0.202510 +0.780119 0.217939 +0.780115 0.233369 +0.780113 0.248798 +0.780113 0.264227 +0.780121 0.279660 +0.780135 0.295121 +0.780016 0.310734 +0.779943 0.001686 +0.780093 0.017294 +0.780074 0.032770 +0.780062 0.048210 +0.780055 0.063642 +0.780051 0.079072 +0.780049 0.094499 +0.780050 0.109922 +0.460261 0.739685 +0.449097 0.731572 +0.449781 0.730888 +0.460701 0.738823 +0.440986 0.720405 +0.441847 0.719966 +0.436722 0.707278 +0.437677 0.707127 +0.436723 0.693476 +0.437678 0.693628 +0.440989 0.680351 +0.441851 0.680790 +0.449102 0.669186 +0.449786 0.669870 +0.460269 0.661074 +0.460708 0.661936 +0.473395 0.656811 +0.473547 0.657766 +0.487197 0.656812 +0.487046 0.657767 +0.500323 0.661078 +0.499883 0.661940 +0.511488 0.669191 +0.510804 0.669875 +0.519599 0.680358 +0.518737 0.680797 +0.523863 0.693484 +0.522907 0.693635 +0.523861 0.707286 +0.522906 0.707134 +0.519595 0.720411 +0.518734 0.719972 +0.511482 0.731576 +0.510798 0.730892 +0.500316 0.739688 +0.499876 0.738826 +0.487189 0.743952 +0.487038 0.742996 +0.473387 0.743951 +0.473538 0.742995 +0.444489 0.736186 +0.435178 0.723369 +0.430282 0.708303 +0.430282 0.692461 +0.435177 0.677395 +0.444488 0.664578 +0.457304 0.655266 +0.472370 0.650371 +0.488212 0.650370 +0.503279 0.655266 +0.516095 0.664577 +0.525407 0.677393 +0.530302 0.692459 +0.530303 0.708301 +0.525408 0.723367 +0.516097 0.736184 +0.503281 0.745496 +0.488214 0.750391 +0.472372 0.750392 +0.457305 0.745498 +0.480292 0.700381 +0.632063 0.929987 +0.631922 0.926055 +0.638284 0.925827 +0.638425 0.929759 +0.631781 0.922124 +0.638142 0.921895 +0.631639 0.918192 +0.638001 0.917963 +0.631498 0.914260 +0.637860 0.914031 +0.632911 0.953578 +0.632770 0.949646 +0.639132 0.949418 +0.639273 0.953349 +0.632629 0.945715 +0.638991 0.945486 +0.632487 0.941783 +0.638849 0.941554 +0.632346 0.937851 +0.638708 0.937622 +0.632205 0.933919 +0.638566 0.933690 +0.566379 0.959108 +0.566369 0.962460 +0.565078 0.961720 +0.565091 0.959845 +0.496971 0.948074 +0.493273 0.956021 +0.488269 0.951352 +0.490681 0.947292 +0.485426 0.960164 +0.484010 0.953205 +0.404885 0.897626 +0.413771 0.897626 +0.404885 0.911882 +0.476455 0.958874 +0.479576 0.952202 +0.489917 0.932817 +0.496621 0.939030 +0.489650 0.942904 +0.486771 0.939469 +0.469700 0.952670 +0.476632 0.948810 +0.480985 0.931499 +0.482281 0.938499 +0.413771 0.926138 +0.404885 0.926138 +0.473112 0.935589 +0.478064 0.940332 +0.469353 0.943553 +0.475593 0.944343 +0.168505 0.899579 +0.177391 0.899579 +0.177391 0.913835 +0.009385 0.961502 +0.000499 0.961501 +0.000500 0.938410 +0.009385 0.938410 +0.177391 0.928091 +0.168505 0.928091 +0.696622 0.913839 +0.692058 0.923022 +0.692058 0.908767 +0.694974 0.908767 +0.706270 0.900559 +0.715149 0.894511 +0.710585 0.903694 +0.059827 0.958874 +0.062012 0.962030 +0.060362 0.964309 +0.057153 0.959746 +0.065634 0.963299 +0.065642 0.966111 +0.069310 0.962194 +0.070965 0.964468 +0.071639 0.959144 +0.074314 0.960012 +0.071728 0.955307 +0.074402 0.954435 +0.069544 0.952150 +0.071192 0.949871 +0.065921 0.950882 +0.065916 0.948069 +0.062244 0.951983 +0.060587 0.949711 +0.059917 0.955037 +0.057241 0.954169 +0.692058 0.894511 +0.696622 0.903694 +0.700937 0.900559 +0.715149 0.908767 +0.712233 0.908767 +0.715149 0.923022 +0.706270 0.916974 +0.710585 0.913839 +0.700937 0.916974 +0.918768 0.954666 +0.921089 0.957872 +0.918117 0.958839 +0.916931 0.957191 +0.921097 0.961827 +0.918127 0.960863 +0.918768 0.965037 +0.916933 0.962511 +0.914997 0.966257 +0.915000 0.963133 +0.911232 0.965033 +0.913069 0.962509 +0.908911 0.961827 +0.911883 0.960860 +0.908903 0.957872 +0.911873 0.958837 +0.911232 0.954663 +0.913067 0.957188 +0.915003 0.953442 +0.915000 0.956567 +0.568381 0.958020 +0.569614 0.959734 +0.567670 0.959848 +0.569625 0.961837 +0.567657 0.961723 +0.568383 0.963550 +0.566374 0.964196 +0.564367 0.963548 +0.563134 0.961834 +0.563123 0.959731 +0.564365 0.958018 +0.566374 0.957372 +0.280887 0.927190 +0.287049 0.928788 +0.286062 0.932596 +0.279900 0.930999 +0.285075 0.936405 +0.278912 0.934807 +0.284087 0.940213 +0.277925 0.938616 +0.283100 0.944022 +0.276938 0.942424 +0.282113 0.947830 +0.275951 0.946233 +0.285823 0.908148 +0.291985 0.909745 +0.290998 0.913554 +0.284836 0.911956 +0.290011 0.917362 +0.283849 0.915765 +0.289024 0.921171 +0.282861 0.919573 +0.288036 0.924979 +0.281874 0.923382 +0.718753 0.958860 +0.720040 0.959600 +0.720047 0.961475 +0.718755 0.962211 +0.507388 0.963262 +0.498656 0.962285 +0.499153 0.957215 +0.507909 0.957954 +0.499512 0.952133 +0.508285 0.952633 +0.404885 0.883370 +0.499733 0.947044 +0.508516 0.947305 +0.262276 0.954153 +0.271062 0.954194 +0.271108 0.959288 +0.262324 0.959486 +0.499815 0.941950 +0.508602 0.941972 +0.262373 0.948820 +0.271155 0.949100 +0.404885 0.869115 +0.413771 0.869115 +0.262616 0.943492 +0.271387 0.944011 +0.263003 0.938173 +0.271757 0.938930 +0.177391 0.885324 +0.148970 0.961164 +0.148970 0.938073 +0.157856 0.938073 +0.157856 0.961164 +0.168505 0.871068 +0.177391 0.871068 +0.906301 0.963509 +0.901206 0.963508 +0.901088 0.954722 +0.906422 0.954723 +0.555430 0.957339 +0.560525 0.957340 +0.560643 0.966126 +0.555309 0.966125 +0.696622 0.932205 +0.694974 0.937278 +0.692058 0.937278 +0.706270 0.945485 +0.710585 0.942351 +0.715149 0.951534 +0.589569 0.960562 +0.592273 0.961339 +0.589226 0.966014 +0.587499 0.963794 +0.584018 0.968002 +0.583923 0.965191 +0.578634 0.966551 +0.580209 0.964221 +0.575132 0.962214 +0.577775 0.961252 +0.574845 0.956645 +0.577548 0.957421 +0.577890 0.951970 +0.579619 0.954189 +0.583102 0.949981 +0.583194 0.952792 +0.588481 0.951434 +0.586907 0.953765 +0.591986 0.955768 +0.589343 0.956730 +0.692058 0.951534 +0.696622 0.942351 +0.700937 0.945485 +0.712233 0.937278 +0.715149 0.937278 +0.710585 0.932205 +0.706270 0.929071 +0.700937 0.929071 +0.362302 0.956259 +0.364132 0.958788 +0.362942 0.960434 +0.359972 0.959459 +0.362926 0.962457 +0.359954 0.963414 +0.364116 0.964109 +0.362274 0.966630 +0.366048 0.964735 +0.366043 0.967860 +0.367980 0.964116 +0.369810 0.966646 +0.369170 0.962471 +0.372140 0.963446 +0.369186 0.960448 +0.372159 0.959491 +0.367996 0.958796 +0.369838 0.956275 +0.366065 0.958169 +0.366070 0.955045 +0.716754 0.957766 +0.717461 0.959596 +0.715517 0.959476 +0.717468 0.961470 +0.715501 0.961579 +0.716737 0.963296 +0.718745 0.963948 +0.720754 0.963304 +0.721991 0.961594 +0.722007 0.959491 +0.720771 0.957774 +0.718763 0.957123 +0.632063 0.929987 +0.638425 0.929759 +0.638284 0.925827 +0.631922 0.926055 +0.638142 0.921895 +0.631781 0.922124 +0.638001 0.917963 +0.631639 0.918192 +0.637860 0.914031 +0.631498 0.914260 +0.632911 0.953578 +0.639273 0.953349 +0.639132 0.949418 +0.632770 0.949646 +0.638991 0.945486 +0.632629 0.945715 +0.638849 0.941554 +0.632487 0.941783 +0.638708 0.937622 +0.632346 0.937851 +0.638566 0.933690 +0.632205 0.933919 +0.566379 0.959108 +0.565091 0.959845 +0.565078 0.961720 +0.566369 0.962460 +0.496971 0.948074 +0.490681 0.947292 +0.488269 0.951352 +0.493273 0.956021 +0.484010 0.953205 +0.485426 0.960164 +0.404885 0.897626 +0.404885 0.911882 +0.413771 0.897626 +0.479576 0.952202 +0.476455 0.958874 +0.489917 0.932817 +0.486771 0.939469 +0.489650 0.942904 +0.496621 0.939030 +0.476632 0.948810 +0.469700 0.952670 +0.480985 0.931499 +0.482281 0.938499 +0.404885 0.926138 +0.413771 0.926138 +0.473112 0.935589 +0.478064 0.940332 +0.469353 0.943553 +0.475593 0.944343 +0.168505 0.899579 +0.177391 0.913835 +0.177391 0.899579 +0.009385 0.961502 +0.009385 0.938410 +0.000500 0.938410 +0.000499 0.961501 +0.168505 0.928091 +0.177391 0.928091 +0.696622 0.913839 +0.694974 0.908767 +0.692058 0.908767 +0.692058 0.923022 +0.706270 0.900559 +0.710585 0.903694 +0.715149 0.894511 +0.059827 0.958874 +0.057153 0.959746 +0.060362 0.964309 +0.062012 0.962030 +0.065642 0.966111 +0.065634 0.963299 +0.070965 0.964468 +0.069310 0.962194 +0.074314 0.960012 +0.071639 0.959144 +0.074402 0.954435 +0.071728 0.955307 +0.071192 0.949871 +0.069544 0.952150 +0.065916 0.948069 +0.065921 0.950882 +0.060587 0.949711 +0.062244 0.951983 +0.057241 0.954169 +0.059917 0.955037 +0.692058 0.894511 +0.696622 0.903694 +0.700937 0.900559 +0.712233 0.908767 +0.715149 0.908767 +0.715149 0.923022 +0.710585 0.913839 +0.706270 0.916974 +0.700937 0.916974 +0.918768 0.954666 +0.916931 0.957191 +0.918117 0.958839 +0.921089 0.957872 +0.918127 0.960863 +0.921097 0.961827 +0.916933 0.962511 +0.918768 0.965037 +0.915000 0.963133 +0.914997 0.966257 +0.913069 0.962509 +0.911232 0.965033 +0.911883 0.960860 +0.908911 0.961827 +0.911873 0.958837 +0.908903 0.957872 +0.913067 0.957188 +0.911232 0.954663 +0.915000 0.956567 +0.915003 0.953442 +0.568381 0.958020 +0.567670 0.959848 +0.569614 0.959734 +0.567657 0.961723 +0.569625 0.961837 +0.568383 0.963550 +0.566374 0.964196 +0.564367 0.963548 +0.563134 0.961834 +0.563123 0.959731 +0.564365 0.958018 +0.566374 0.957372 +0.280887 0.927190 +0.279900 0.930999 +0.286062 0.932596 +0.287049 0.928788 +0.278912 0.934807 +0.285075 0.936405 +0.277925 0.938616 +0.284087 0.940213 +0.276938 0.942424 +0.283100 0.944022 +0.275951 0.946233 +0.282113 0.947830 +0.285823 0.908148 +0.284836 0.911956 +0.290998 0.913554 +0.291985 0.909745 +0.283849 0.915765 +0.290011 0.917362 +0.282861 0.919573 +0.289024 0.921171 +0.281874 0.923382 +0.288036 0.924979 +0.718753 0.958860 +0.718755 0.962211 +0.720047 0.961475 +0.720040 0.959600 +0.507388 0.963262 +0.507909 0.957954 +0.499153 0.957215 +0.498656 0.962285 +0.508285 0.952633 +0.499512 0.952133 +0.404885 0.883370 +0.508516 0.947305 +0.499733 0.947044 +0.262276 0.954153 +0.262324 0.959486 +0.271108 0.959288 +0.271062 0.954194 +0.508602 0.941972 +0.499815 0.941950 +0.262373 0.948820 +0.271155 0.949100 +0.413771 0.869115 +0.404885 0.869115 +0.262616 0.943492 +0.271387 0.944011 +0.263003 0.938173 +0.271757 0.938930 +0.177391 0.885324 +0.148970 0.961164 +0.157856 0.961164 +0.157856 0.938073 +0.148970 0.938073 +0.177391 0.871068 +0.168505 0.871068 +0.906301 0.963509 +0.906422 0.954723 +0.901088 0.954722 +0.901206 0.963508 +0.555430 0.957339 +0.555309 0.966125 +0.560643 0.966126 +0.560525 0.957340 +0.696622 0.932205 +0.692058 0.937278 +0.694974 0.937278 +0.706270 0.945485 +0.715149 0.951534 +0.710585 0.942351 +0.589569 0.960562 +0.587499 0.963794 +0.589226 0.966014 +0.592273 0.961339 +0.583923 0.965191 +0.584018 0.968002 +0.580209 0.964221 +0.578634 0.966551 +0.577775 0.961252 +0.575132 0.962214 +0.577548 0.957421 +0.574845 0.956645 +0.579619 0.954189 +0.577890 0.951970 +0.583194 0.952792 +0.583102 0.949981 +0.586907 0.953765 +0.588481 0.951434 +0.589343 0.956730 +0.591986 0.955768 +0.692058 0.951534 +0.696622 0.942351 +0.700937 0.945485 +0.715149 0.937278 +0.712233 0.937278 +0.706270 0.929071 +0.710585 0.932205 +0.700937 0.929071 +0.362302 0.956259 +0.359972 0.959459 +0.362942 0.960434 +0.364132 0.958788 +0.359954 0.963414 +0.362926 0.962457 +0.362274 0.966630 +0.364116 0.964109 +0.366043 0.967860 +0.366048 0.964735 +0.369810 0.966646 +0.367980 0.964116 +0.372140 0.963446 +0.369170 0.962471 +0.372159 0.959491 +0.369186 0.960448 +0.369838 0.956275 +0.367996 0.958796 +0.366070 0.955045 +0.366065 0.958169 +0.716754 0.957766 +0.715517 0.959476 +0.717461 0.959596 +0.715501 0.961579 +0.717468 0.961470 +0.716737 0.963296 +0.718745 0.963948 +0.720754 0.963304 +0.721991 0.961594 +0.722007 0.959491 +0.720771 0.957774 +0.718763 0.957123 +0.132693 0.952663 +0.132693 0.959530 +0.121620 0.959530 +0.121620 0.952663 +0.132693 0.966397 +0.121620 0.966397 +0.285070 0.952566 +0.285070 0.959432 +0.273997 0.959432 +0.273997 0.952566 +0.285070 0.966298 +0.273997 0.966298 +0.135295 0.966397 +0.135295 0.959530 +0.146368 0.959530 +0.146368 0.966397 +0.135295 0.952663 +0.146368 0.952663 +0.107945 0.966399 +0.107945 0.959532 +0.119018 0.959532 +0.119018 0.966399 +0.107945 0.952665 +0.119018 0.952665 +0.208648 0.317615 +0.208648 0.394537 +0.104179 0.394537 +0.104179 0.317615 +0.557060 0.629026 +0.550427 0.636883 +0.458267 0.507681 +0.981914 0.891815 +0.904995 0.891815 +0.909837 0.886973 +0.977072 0.886973 +0.079456 0.943218 +0.012221 0.943218 +0.012221 0.873950 +0.079456 0.873950 +0.660460 0.010936 +0.672017 0.010936 +0.672017 0.182193 +0.660460 0.182193 +0.682189 0.010936 +0.682189 0.182193 +0.689758 0.010936 +0.689758 0.182193 +0.237308 0.022007 +0.725671 0.015541 +0.725671 0.182193 +0.237308 0.162944 +0.000500 0.009547 +0.013641 0.009547 +0.013641 0.159624 +0.000500 0.159624 +0.208648 0.309700 +0.104179 0.309700 +0.000500 0.309700 +0.013641 0.309700 +0.013641 0.317615 +0.000500 0.317615 +0.689758 0.353449 +0.731569 0.353449 +0.731569 0.362480 +0.689758 0.362480 +0.682189 0.353449 +0.682189 0.362480 +0.672017 0.353449 +0.672017 0.362480 +0.660460 0.353449 +0.660460 0.362480 +0.660460 0.001905 +0.672017 0.001905 +0.682189 0.001905 +0.689758 0.001905 +0.731569 0.001905 +0.731569 0.010936 +0.000500 0.001632 +0.013641 0.001632 +0.192903 0.001632 +0.192903 0.009547 +0.104179 0.009547 +0.104179 0.001632 +0.723350 0.643925 +0.701826 0.619001 +0.806289 0.619001 +0.806289 0.643925 +0.577018 0.001905 +0.577018 0.010936 +0.577018 0.182193 +0.577018 0.362480 +0.577018 0.353449 +0.977072 0.756384 +0.981914 0.756384 +0.533820 0.778107 +0.603089 0.778107 +0.603089 0.908697 +0.533820 0.908697 +0.604148 0.777279 +0.671383 0.777279 +0.671383 0.907868 +0.604148 0.907868 +0.397965 0.648642 +0.397965 0.779232 +0.328697 0.779232 +0.328697 0.648642 +0.904995 0.756384 +0.909837 0.756384 +0.700798 0.640904 +0.596334 0.640904 +0.596334 0.505473 +0.700798 0.505473 +0.211483 0.403252 +0.288402 0.403252 +0.288402 0.538683 +0.211483 0.538683 +0.296316 0.403252 +0.296316 0.538683 +0.593699 0.566089 +0.593699 0.552948 +0.865924 0.047646 +0.873850 0.047646 +0.873850 0.176563 +0.865924 0.176563 +0.541513 0.642008 +0.531386 0.643788 +0.458267 0.643788 +0.781922 0.009447 +0.864861 0.009447 +0.864861 0.159517 +0.781922 0.159517 +0.819798 0.866104 +0.807318 0.884327 +0.807318 0.755597 +0.819798 0.755597 +0.723350 0.754432 +0.701826 0.754432 +0.766293 0.463387 +0.766293 0.313317 +0.876800 0.313317 +0.876800 0.463387 +0.965556 0.006808 +0.990480 0.006808 +0.990480 0.156878 +0.965556 0.156878 +0.814018 0.891028 +0.902738 0.866104 +0.902738 0.891028 +0.197641 0.001632 +0.197641 0.009547 +0.873850 0.042901 +0.865924 0.042901 +0.593699 0.462414 +0.593699 0.373694 +0.809280 0.889065 +0.593699 0.474267 +0.092325 0.009547 +0.092325 0.001632 +0.104179 0.159624 +0.092325 0.159624 +0.092325 0.317615 +0.092325 0.309700 +0.307325 0.939462 +0.307325 0.960478 +0.303300 0.960478 +0.303300 0.939462 +0.725671 0.348844 +0.237308 0.303882 +0.766293 0.613457 +0.876800 0.613457 +0.864861 0.309587 +0.781922 0.309587 +0.990480 0.306948 +0.965556 0.306948 +0.084850 0.026558 +0.021116 0.026558 +0.084850 0.119406 +0.021116 0.119406 +0.729253 0.015541 +0.692074 0.015541 +0.731569 0.182193 +0.729253 0.182193 +0.692074 0.182193 +0.729253 0.348844 +0.692074 0.348844 +0.320248 0.906802 +0.287672 0.850843 +0.290810 0.849016 +0.323386 0.904975 +0.742850 0.158921 +0.742850 0.001838 +0.746226 0.001838 +0.746226 0.158921 +0.297990 0.878192 +0.265414 0.934151 +0.262276 0.932324 +0.294852 0.876365 +0.742850 0.316004 +0.746226 0.316004 +0.992905 0.363141 +0.992905 0.299426 +0.996536 0.299426 +0.996536 0.363141 +0.996537 0.001798 +0.996537 0.094639 +0.992905 0.094639 +0.992905 0.001798 +0.879323 0.143226 +0.879323 0.206949 +0.875692 0.206949 +0.875692 0.143226 +0.992905 0.194271 +0.992905 0.101429 +0.996537 0.101429 +0.996537 0.194271 +0.215391 0.681653 +0.279122 0.681653 +0.257768 0.685226 +0.236745 0.685226 +0.279122 0.774498 +0.257768 0.689252 +0.215391 0.774498 +0.236745 0.689252 +0.664708 0.933914 +0.664708 0.912923 +0.666244 0.912923 +0.666244 0.933914 +0.789312 0.000485 +0.789312 0.004488 +0.787782 0.004488 +0.787782 0.000485 +0.666244 0.940273 +0.666244 0.961264 +0.664708 0.961264 +0.664708 0.940273 +0.791689 0.004488 +0.791689 0.000485 +0.793219 0.000485 +0.793219 0.004488 +0.211483 0.317615 +0.315952 0.317615 +0.315952 0.394537 +0.211483 0.394537 +0.359475 0.629026 +0.366108 0.636883 +0.981914 0.620954 +0.977072 0.625795 +0.909837 0.625795 +0.904995 0.620954 +0.147830 0.877853 +0.147830 0.947121 +0.080595 0.947121 +0.080595 0.877853 +0.493577 0.010936 +0.493577 0.182193 +0.482020 0.182193 +0.482020 0.010936 +0.471848 0.182193 +0.471848 0.010936 +0.464279 0.182193 +0.464279 0.010936 +0.238028 0.304601 +0.238028 0.162944 +0.428365 0.182193 +0.428365 0.015541 +0.419631 0.009547 +0.419631 0.159624 +0.406490 0.159624 +0.406490 0.009547 +0.211483 0.309700 +0.315952 0.309700 +0.419631 0.309700 +0.419631 0.317615 +0.406490 0.317615 +0.406490 0.309700 +0.464279 0.353449 +0.464279 0.362480 +0.422467 0.362480 +0.422467 0.353449 +0.471848 0.353449 +0.471848 0.362480 +0.482020 0.353449 +0.482020 0.362480 +0.493577 0.353449 +0.493577 0.362480 +0.493577 0.001905 +0.482020 0.001905 +0.471848 0.001905 +0.464279 0.001905 +0.422467 0.010936 +0.422467 0.001905 +0.419631 0.001632 +0.406490 0.001632 +0.227228 0.001632 +0.315952 0.001632 +0.315952 0.009547 +0.227228 0.009547 +0.723350 0.864939 +0.806289 0.864939 +0.806289 0.889863 +0.701826 0.889863 +0.533820 0.647518 +0.603089 0.647518 +0.604148 0.646689 +0.671383 0.646689 +0.397965 0.909821 +0.328697 0.909821 +0.700798 0.370042 +0.596334 0.370042 +0.211483 0.674114 +0.288402 0.674114 +0.296316 0.674114 +0.322836 0.566089 +0.322836 0.552948 +0.865924 0.305480 +0.873850 0.305480 +0.375021 0.642008 +0.385148 0.643788 +0.964493 0.008762 +0.964493 0.158832 +0.881553 0.158832 +0.881553 0.008762 +0.819798 0.645090 +0.807318 0.626866 +0.987308 0.463387 +0.987308 0.313317 +0.025423 0.323283 +0.025423 0.473353 +0.000499 0.473353 +0.000499 0.323283 +0.814018 0.620166 +0.902738 0.620166 +0.902738 0.645090 +0.222490 0.009547 +0.222490 0.001632 +0.873850 0.310225 +0.865924 0.310225 +0.322836 0.462414 +0.322836 0.373694 +0.809280 0.622128 +0.322836 0.474267 +0.327806 0.009547 +0.327806 0.001632 +0.327806 0.159624 +0.315952 0.159624 +0.327806 0.317615 +0.327806 0.309700 +0.928556 0.962431 +0.924531 0.962431 +0.924531 0.941415 +0.928556 0.941415 +0.238028 0.021288 +0.297513 0.021288 +0.987308 0.613457 +0.964493 0.308902 +0.881553 0.308902 +0.025423 0.623423 +0.000499 0.623423 +0.399015 0.026558 +0.335281 0.026558 +0.335281 0.119406 +0.399015 0.119406 +0.461962 0.015541 +0.424784 0.015541 +0.424784 0.182193 +0.422467 0.182193 +0.461962 0.182193 +0.424784 0.348844 +0.461962 0.348844 +0.259553 0.922430 +0.256415 0.920603 +0.288992 0.864644 +0.292130 0.866471 +0.752087 0.158921 +0.748711 0.158921 +0.748711 0.001838 +0.752087 0.001838 +0.500610 0.870378 +0.503748 0.868551 +0.536324 0.924510 +0.533186 0.926337 +0.752087 0.316004 +0.748711 0.316004 +0.879323 0.136621 +0.875692 0.136621 +0.875692 0.072898 +0.879323 0.072898 +0.875692 0.214685 +0.879323 0.214685 +0.879323 0.307518 +0.875692 0.307518 +0.875692 0.002570 +0.879323 0.002570 +0.879323 0.066293 +0.875692 0.066293 +0.996537 0.293902 +0.992905 0.293902 +0.992905 0.201061 +0.996537 0.201061 +0.511595 0.753933 +0.490241 0.757506 +0.469218 0.757506 +0.447864 0.753933 +0.469218 0.761532 +0.447864 0.846777 +0.490241 0.761532 +0.511595 0.846777 +0.291162 0.961264 +0.289626 0.961264 +0.289626 0.940273 +0.291162 0.940273 +0.795596 0.000485 +0.797126 0.000485 +0.797126 0.004488 +0.795596 0.004488 +0.865924 0.015102 +0.867462 0.015102 +0.867462 0.036111 +0.865924 0.036111 +0.890900 0.004667 +0.889367 0.004667 +0.889367 0.000655 +0.890900 0.000655 +0.051594 0.951886 +0.054327 0.958485 +0.053291 0.958485 +0.050861 0.952619 +0.051594 0.965083 +0.050861 0.964351 +0.044995 0.967817 +0.044995 0.966780 +0.038397 0.965083 +0.039129 0.964351 +0.035663 0.958485 +0.036700 0.958485 +0.038397 0.951886 +0.039129 0.952619 +0.044995 0.949153 +0.044995 0.950189 +0.971055 0.952907 +0.969840 0.953957 +0.964934 0.951570 +0.965051 0.949968 +0.973222 0.959231 +0.971620 0.959114 +0.970283 0.965235 +0.969233 0.964020 +0.963959 0.967402 +0.964076 0.965801 +0.957955 0.964463 +0.959170 0.963413 +0.955788 0.958139 +0.957390 0.958256 +0.958727 0.952135 +0.959777 0.953350 +0.964505 0.958685 +0.811412 0.958332 +0.811412 0.964435 +0.801457 0.964435 +0.801457 0.958332 +0.811412 0.970538 +0.801457 0.970538 +0.836810 0.956502 +0.836810 0.962606 +0.826853 0.962606 +0.826853 0.956502 +0.836810 0.968710 +0.826853 0.968710 +0.813178 0.970538 +0.813178 0.964435 +0.823133 0.964435 +0.823133 0.970538 +0.813178 0.958332 +0.823133 0.958332 +0.889367 0.966882 +0.889367 0.960777 +0.899324 0.960777 +0.899324 0.966882 +0.889367 0.954672 +0.899324 0.954672 +0.044503 0.283515 +0.051104 0.280780 +0.053839 0.274179 +0.051104 0.267577 +0.044503 0.264843 +0.037901 0.267577 +0.035167 0.274179 +0.037901 0.280780 +0.324799 0.368956 +0.329537 0.366993 +0.591736 0.368956 +0.586998 0.366993 +0.458267 0.366993 +0.039703 0.672232 +0.027849 0.672232 +0.027849 0.536801 +0.194462 0.635594 +0.131524 0.672232 +0.202319 0.628961 +0.207444 0.620047 +0.209223 0.609920 +0.209223 0.536801 +0.118384 0.672232 +0.118384 0.401370 +0.131524 0.401370 +0.194462 0.438008 +0.202319 0.444641 +0.207444 0.453555 +0.209223 0.463682 +0.027849 0.401370 +0.039703 0.401370 +0.007270 0.903167 +0.007400 0.918262 +0.000637 0.918748 +0.000499 0.902796 +0.989918 0.706688 +0.990958 0.721748 +0.984237 0.722642 +0.983138 0.706727 +0.994635 0.621919 +0.993825 0.636993 +0.987045 0.637058 +0.987900 0.621128 +0.651961 0.925921 +0.651961 0.941019 +0.645867 0.939628 +0.645867 0.927312 +0.161214 0.893599 +0.164573 0.908318 +0.158322 0.908318 +0.155582 0.896312 +0.203669 0.029870 +0.207029 0.015151 +0.212661 0.017864 +0.209920 0.029870 +0.785256 0.934121 +0.784959 0.946432 +0.768335 0.944445 +0.768556 0.935302 +0.998334 0.905811 +0.999500 0.918071 +0.982758 0.918071 +0.981892 0.908967 +0.894185 0.922350 +0.892897 0.934597 +0.876486 0.931278 +0.877443 0.922182 +0.503981 0.915539 +0.504015 0.906821 +0.507771 0.907164 +0.507739 0.915226 +0.693708 0.866255 +0.693024 0.857564 +0.696795 0.857595 +0.697428 0.865633 +0.983941 0.844331 +0.984723 0.835649 +0.988436 0.836312 +0.987712 0.844342 +0.736376 0.905550 +0.744477 0.905542 +0.743738 0.908796 +0.737124 0.908802 +0.756830 0.915374 +0.758623 0.923272 +0.755286 0.923271 +0.753825 0.916822 +0.722257 0.923264 +0.724051 0.915384 +0.727057 0.916832 +0.725594 0.923265 +0.519741 0.952623 +0.519783 0.959200 +0.516310 0.959222 +0.516269 0.952645 +0.260208 0.933047 +0.260091 0.939623 +0.256619 0.939561 +0.256736 0.932985 +0.533385 0.943504 +0.533385 0.950081 +0.529913 0.950081 +0.529913 0.943504 +0.990837 0.605529 +0.997819 0.605509 +0.997033 0.608749 +0.987412 0.738194 +0.993558 0.734880 +0.994394 0.738107 +0.728018 0.910399 +0.730625 0.908315 +0.732715 0.910917 +0.730091 0.913009 +0.750234 0.908298 +0.752846 0.910377 +0.750775 0.912991 +0.748152 0.910903 +0.002867 0.934463 +0.009202 0.931526 +0.002460 0.887046 +0.008844 0.889874 +0.215376 0.004685 +0.219273 0.009572 +0.646153 0.913860 +0.641266 0.917757 +0.646153 0.953080 +0.641266 0.949183 +0.152867 0.883133 +0.148970 0.888020 +0.889820 0.944746 +0.873739 0.939939 +0.783510 0.923661 +0.766944 0.926360 +0.782709 0.956796 +0.766293 0.953299 +0.995359 0.895632 +0.979230 0.900279 +0.986550 0.828883 +0.990092 0.830179 +0.508813 0.921488 +0.505166 0.922446 +0.505255 0.899924 +0.508895 0.900911 +0.699015 0.871785 +0.695459 0.873040 +0.533385 0.954949 +0.529913 0.954949 +0.519710 0.947756 +0.516238 0.947778 +0.519813 0.964067 +0.516341 0.964089 +0.260295 0.928181 +0.256823 0.928119 +0.717465 0.897202 +0.720068 0.895121 +0.983623 0.820937 +0.983309 0.814694 +0.500610 0.936269 +0.501507 0.930083 +0.760759 0.895079 +0.763367 0.897154 +0.692058 0.887192 +0.692442 0.880953 +0.501657 0.892258 +0.500809 0.886065 +0.991970 0.960074 +0.989326 0.962324 +0.981348 0.952953 +0.985447 0.949463 +0.841231 0.924327 +0.844702 0.924420 +0.846261 0.937536 +0.840880 0.937391 +0.740462 0.920617 +0.738356 0.923268 +0.973370 0.943581 +0.976014 0.941330 +0.742582 0.923269 +0.526014 0.952658 +0.522542 0.952717 +0.522321 0.939650 +0.527703 0.939559 +0.180227 0.923865 +0.180444 0.907914 +0.187205 0.908435 +0.186999 0.923529 +0.984054 0.690800 +0.990785 0.691617 +0.988205 0.652969 +0.994923 0.652049 +0.652987 0.927006 +0.659081 0.928396 +0.659081 0.940712 +0.652987 0.942103 +0.161214 0.923037 +0.155582 0.920325 +0.212661 0.041877 +0.207029 0.044589 +0.599244 0.938420 +0.582587 0.936732 +0.582644 0.927587 +0.599320 0.926105 +0.998335 0.930331 +0.981892 0.927176 +0.876668 0.913070 +0.893142 0.910079 +0.303038 0.906258 +0.306791 0.906631 +0.306694 0.914693 +0.302933 0.914975 +0.693853 0.848885 +0.697562 0.849569 +0.988389 0.852377 +0.984673 0.853018 +0.736369 0.940984 +0.737118 0.937733 +0.743731 0.937742 +0.744469 0.940996 +0.756827 0.931169 +0.753822 0.929720 +0.727054 0.929699 +0.724048 0.931145 +0.297086 0.955715 +0.293614 0.955657 +0.293724 0.949081 +0.297196 0.949139 +0.259974 0.946199 +0.256502 0.946137 +0.529913 0.936927 +0.533385 0.936927 +0.991440 0.668508 +0.997573 0.665170 +0.998421 0.668395 +0.987050 0.675213 +0.994033 0.675220 +0.993234 0.678456 +0.728012 0.936132 +0.730086 0.933522 +0.732709 0.935616 +0.730619 0.938217 +0.750228 0.938242 +0.748147 0.935637 +0.750771 0.933549 +0.752841 0.936165 +0.182755 0.892211 +0.189074 0.895180 +0.188505 0.936830 +0.182107 0.939625 +0.219273 0.050168 +0.215376 0.055055 +0.658795 0.914944 +0.663683 0.918841 +0.663683 0.950267 +0.658795 0.954164 +0.152867 0.933503 +0.148970 0.928616 +0.874094 0.904355 +0.890268 0.899871 +0.597181 0.948822 +0.580705 0.945622 +0.580872 0.918675 +0.597386 0.915678 +0.995360 0.940510 +0.979231 0.935864 +0.990010 0.858519 +0.986461 0.859795 +0.307966 0.900388 +0.304334 0.899371 +0.307717 0.920963 +0.304062 0.921892 +0.699252 0.843445 +0.695717 0.842130 +0.529913 0.932060 +0.533385 0.932060 +0.297005 0.960582 +0.293533 0.960524 +0.293805 0.944215 +0.297277 0.944273 +0.259887 0.951065 +0.256415 0.951003 +0.717454 0.949324 +0.720056 0.951407 +0.983487 0.867724 +0.983138 0.873965 +0.300001 0.885477 +0.300799 0.891676 +0.760747 0.951467 +0.763355 0.949392 +0.692554 0.827923 +0.692833 0.834168 +0.300341 0.929499 +0.299393 0.935677 +0.830127 0.926191 +0.836031 0.937158 +0.830956 0.938953 +0.826853 0.927349 +0.840528 0.950455 +0.843999 0.950549 +0.740461 0.925920 +0.835058 0.950557 +0.838332 0.949399 +0.525571 0.926524 +0.522099 0.926583 +0.431231 0.866840 +0.445125 0.856633 +0.450470 0.868776 +0.441606 0.875713 +0.422467 0.899305 +0.423004 0.882062 +0.436019 0.885501 +0.435512 0.896850 +0.429280 0.915188 +0.440264 0.907076 +0.459144 0.931091 +0.442346 0.926669 +0.448571 0.914677 +0.459520 0.917669 +0.462033 0.853301 +0.461660 0.866728 +0.498782 0.885078 +0.498198 0.902376 +0.485189 0.898879 +0.485754 0.887537 +0.476028 0.927749 +0.470691 0.915599 +0.478811 0.857709 +0.472608 0.869709 +0.491892 0.869157 +0.480922 0.877300 +0.489920 0.917574 +0.479580 0.908668 +0.215731 0.874022 +0.215688 0.862430 +0.268038 0.862238 +0.268080 0.873829 +0.215646 0.850897 +0.267995 0.850704 +0.215603 0.839364 +0.267953 0.839171 +0.215561 0.827772 +0.267910 0.827579 +0.215518 0.816180 +0.267867 0.815988 +0.215476 0.804647 +0.267825 0.804454 +0.215433 0.793113 +0.267782 0.792921 +0.215391 0.781522 +0.267740 0.781329 +0.994122 0.892536 +0.994123 0.943606 +0.889063 0.896762 +0.888552 0.947830 +0.962747 0.900356 +0.971138 0.907204 +0.964821 0.912224 +0.959367 0.907450 +0.975614 0.917024 +0.975627 0.927783 +0.968011 0.926010 +0.968196 0.918662 +0.970830 0.937445 +0.964550 0.932390 +0.962281 0.943977 +0.951835 0.946380 +0.951817 0.938591 +0.959022 0.937113 +0.952230 0.897924 +0.952249 0.905712 +0.928452 0.927279 +0.928438 0.916521 +0.936055 0.918294 +0.935869 0.925641 +0.941319 0.943947 +0.944699 0.936853 +0.941785 0.900326 +0.945044 0.907191 +0.933235 0.906858 +0.939515 0.911913 +0.932927 0.937100 +0.939245 0.932079 +0.952033 0.922152 +0.924491 0.934810 +0.917091 0.903361 +0.924491 0.912207 +0.927070 0.923509 +0.698788 0.709648 +0.694012 0.709648 +0.694012 0.647295 +0.698788 0.647295 +0.687268 0.826824 +0.687268 0.889177 +0.672522 0.889177 +0.672522 0.826824 +0.676314 0.821769 +0.680266 0.816993 +0.691060 0.816993 +0.691060 0.821769 +0.072454 0.795840 +0.061660 0.795840 +0.057708 0.791064 +0.072454 0.791064 +0.996889 0.808217 +0.986095 0.808227 +0.986040 0.745874 +0.996834 0.745864 +0.673633 0.820658 +0.677585 0.815882 +0.672522 0.817977 +0.676474 0.813201 +0.147726 0.795152 +0.091164 0.803220 +0.090363 0.800441 +0.156548 0.791013 +0.157380 0.793865 +0.690171 0.889177 +0.690171 0.826824 +0.053916 0.794856 +0.055026 0.792175 +0.058978 0.796951 +0.057868 0.799632 +0.192028 0.949884 +0.192025 0.946982 +0.254378 0.946908 +0.254381 0.949810 +0.983193 0.808229 +0.983138 0.745876 +0.179142 0.714903 +0.174366 0.714903 +0.174366 0.652550 +0.179142 0.652550 +0.287793 0.845108 +0.273047 0.845121 +0.272992 0.782768 +0.287738 0.782755 +0.676314 0.742225 +0.691060 0.742225 +0.691060 0.747001 +0.680266 0.747001 +0.072454 0.865832 +0.072454 0.870608 +0.057708 0.870608 +0.061660 0.865832 +0.525078 0.876797 +0.514284 0.876788 +0.514337 0.814435 +0.525131 0.814444 +0.191951 0.884574 +0.254304 0.884500 +0.672522 0.746017 +0.676474 0.750793 +0.148980 0.872826 +0.098071 0.869698 +0.057868 0.862040 +0.053916 0.866816 +0.677585 0.748112 +0.673633 0.743336 +0.097426 0.872524 +0.157835 0.873170 +0.157218 0.876075 +0.270145 0.845123 +0.270090 0.782771 +0.058978 0.864721 +0.055026 0.869498 +0.191948 0.881671 +0.254301 0.881598 +0.527981 0.876799 +0.528033 0.814446 +0.171729 0.816344 +0.172486 0.849324 +0.163836 0.848096 +0.163367 0.818303 +0.162870 0.800041 +0.155073 0.803347 +0.045765 0.861374 +0.045766 0.800298 +0.156948 0.864168 +0.164544 0.866972 +0.211818 0.193373 +0.211818 0.132298 +0.219968 0.126856 +0.219968 0.198816 +0.037617 0.815538 +0.037617 0.846134 +0.203669 0.147538 +0.203669 0.178133 +0.895228 0.948902 +0.895228 0.898115 +0.906820 0.898115 +0.906820 0.948902 +0.917091 0.943656 +0.293533 0.936439 +0.293533 0.929491 +0.297973 0.929491 +0.297973 0.936439 +0.293533 0.916434 +0.297973 0.916434 +0.514818 0.922294 +0.514818 0.935352 +0.510377 0.935352 +0.510377 0.922294 +0.514818 0.942300 +0.510377 0.942300 +0.510377 0.964382 +0.510377 0.956839 +0.514821 0.956839 +0.514821 0.964382 +0.510377 0.949296 +0.514821 0.949296 +0.672506 0.949614 +0.668615 0.942875 +0.679818 0.942875 +0.679818 0.952275 +0.327676 0.916667 +0.331567 0.923406 +0.330146 0.923704 +0.326749 0.917820 +0.329429 0.936071 +0.328966 0.930396 +0.323761 0.934763 +0.311299 0.936071 +0.316967 0.934763 +0.311761 0.930396 +0.309161 0.923406 +0.310582 0.923704 +0.313052 0.916667 +0.313979 0.917820 +0.320364 0.914006 +0.320364 0.915496 +0.930392 0.961061 +0.930392 0.954607 +0.931573 0.954607 +0.931573 0.961061 +0.930392 0.947267 +0.931573 0.947267 +0.930392 0.942477 +0.931573 0.942477 +0.867001 0.000872 +0.867001 0.007667 +0.865924 0.007667 +0.865924 0.000872 +0.300575 0.940502 +0.300575 0.945292 +0.299393 0.945292 +0.299393 0.940502 +0.300575 0.952632 +0.299393 0.952632 +0.300575 0.959086 +0.299393 0.959086 +0.750664 0.960357 +0.750664 0.953771 +0.751775 0.953771 +0.751775 0.960357 +0.750664 0.947184 +0.751775 0.947184 +0.731499 0.947419 +0.737384 0.944022 +0.737896 0.947540 +0.734129 0.949716 +0.744075 0.945202 +0.742181 0.948296 +0.748443 0.950406 +0.744977 0.951629 +0.748443 0.957201 +0.744977 0.955979 +0.744075 0.962406 +0.742181 0.959312 +0.737384 0.963586 +0.737896 0.960067 +0.731499 0.960189 +0.734129 0.957892 +0.729175 0.953804 +0.732641 0.953804 +0.191948 0.968733 +0.191948 0.964600 +0.201486 0.964600 +0.201486 0.968733 +0.191948 0.959901 +0.201486 0.959901 +0.191948 0.956834 +0.201486 0.956834 +0.999210 0.958446 +0.994859 0.958446 +0.994859 0.949750 +0.999210 0.949750 +0.213207 0.956217 +0.213207 0.959285 +0.203669 0.959285 +0.203669 0.956217 +0.213207 0.963984 +0.203669 0.963984 +0.213207 0.968117 +0.203669 0.968117 +0.594380 0.955474 +0.598598 0.955474 +0.598598 0.964445 +0.594380 0.964445 +0.602815 0.955474 +0.602815 0.964445 +0.789270 0.955945 +0.793038 0.953770 +0.794037 0.960034 +0.797322 0.954526 +0.800119 0.957858 +0.800119 0.962209 +0.797322 0.965542 +0.793038 0.966297 +0.789270 0.964122 +0.787782 0.960034 +0.293533 0.896429 +0.297973 0.896429 +0.297973 0.903376 +0.293533 0.903376 +0.510377 0.909237 +0.514818 0.909237 +0.510377 0.902289 +0.514818 0.902289 +0.553892 0.963786 +0.549448 0.963786 +0.549448 0.956243 +0.553892 0.956243 +0.549448 0.948700 +0.553892 0.948700 +0.668615 0.917545 +0.679818 0.917545 +0.679818 0.930210 +0.670753 0.930210 +0.327676 0.955474 +0.326749 0.954322 +0.330146 0.948437 +0.331567 0.948736 +0.328966 0.941746 +0.323761 0.937378 +0.316967 0.937378 +0.311761 0.941746 +0.310582 0.948437 +0.309161 0.948736 +0.313979 0.954322 +0.313052 0.955474 +0.320364 0.956646 +0.320364 0.958136 +0.188041 0.941660 +0.189222 0.941660 +0.189222 0.948114 +0.188041 0.948114 +0.189222 0.955454 +0.188041 0.955454 +0.189222 0.960244 +0.188041 0.960244 +0.203669 0.001931 +0.204746 0.001931 +0.204746 0.008726 +0.203669 0.008726 +0.185315 0.962485 +0.184134 0.962485 +0.184134 0.957695 +0.185315 0.957695 +0.184134 0.950355 +0.185315 0.950355 +0.184134 0.943901 +0.185315 0.943901 +0.181337 0.959136 +0.180227 0.959136 +0.180227 0.952549 +0.181337 0.952549 +0.180227 0.945962 +0.181337 0.945962 +0.029164 0.951748 +0.026535 0.954044 +0.022767 0.951869 +0.023280 0.948351 +0.018483 0.952625 +0.016588 0.949530 +0.015686 0.955958 +0.012221 0.954735 +0.015686 0.960308 +0.012221 0.961530 +0.018483 0.963641 +0.016588 0.966735 +0.022767 0.964396 +0.023280 0.967915 +0.026535 0.962221 +0.029164 0.964518 +0.028023 0.958133 +0.031488 0.958133 +0.384477 0.958202 +0.379711 0.962290 +0.380709 0.956027 +0.376425 0.956782 +0.373628 0.960115 +0.373628 0.964466 +0.376425 0.967798 +0.380709 0.968554 +0.384477 0.966379 +0.385965 0.962290 +0.215391 0.956980 +0.224929 0.956980 +0.224929 0.961113 +0.215391 0.961113 +0.224929 0.965812 +0.215391 0.965812 +0.224929 0.968880 +0.215391 0.968880 +0.954278 0.953471 +0.954278 0.962167 +0.949927 0.962167 +0.949927 0.953471 +0.236650 0.970532 +0.227112 0.970532 +0.227112 0.967465 +0.236650 0.967465 +0.227112 0.962765 +0.236650 0.962765 +0.227112 0.958632 +0.236650 0.958632 +0.668615 0.963923 +0.668615 0.954953 +0.672833 0.954953 +0.672833 0.963923 +0.677050 0.954953 +0.677050 0.963923 +0.672506 0.910806 +0.679818 0.908145 +0.687130 0.910806 +0.691021 0.917545 +0.688883 0.930210 +0.691021 0.942875 +0.687130 0.949614 +0.293533 0.936439 +0.297973 0.936439 +0.297973 0.929491 +0.293533 0.929491 +0.297973 0.916434 +0.293533 0.916434 +0.514818 0.922294 +0.510377 0.922294 +0.510377 0.935352 +0.514818 0.935352 +0.510377 0.942300 +0.514818 0.942300 +0.510377 0.964382 +0.514821 0.964382 +0.514821 0.956839 +0.510377 0.956839 +0.514821 0.949296 +0.510377 0.949296 +0.672506 0.949614 +0.679818 0.952275 +0.679818 0.942875 +0.668615 0.942875 +0.327676 0.916667 +0.326749 0.917820 +0.330146 0.923704 +0.331567 0.923406 +0.328966 0.930396 +0.329429 0.936071 +0.323761 0.934763 +0.316967 0.934763 +0.311299 0.936071 +0.311761 0.930396 +0.310582 0.923704 +0.309161 0.923406 +0.313979 0.917820 +0.313052 0.916667 +0.320364 0.915496 +0.320364 0.914006 +0.930392 0.961061 +0.931573 0.961061 +0.931573 0.954607 +0.930392 0.954607 +0.931573 0.947267 +0.930392 0.947267 +0.931573 0.942477 +0.930392 0.942477 +0.867001 0.000872 +0.865924 0.000872 +0.865924 0.007667 +0.867001 0.007667 +0.300575 0.940502 +0.299393 0.940502 +0.299393 0.945292 +0.300575 0.945292 +0.299393 0.952632 +0.300575 0.952632 +0.299393 0.959086 +0.300575 0.959086 +0.750664 0.960357 +0.751775 0.960357 +0.751775 0.953771 +0.750664 0.953771 +0.751775 0.947184 +0.750664 0.947184 +0.731499 0.947419 +0.734129 0.949716 +0.737896 0.947540 +0.737384 0.944022 +0.742181 0.948296 +0.744075 0.945202 +0.744977 0.951629 +0.748443 0.950406 +0.744977 0.955979 +0.748443 0.957201 +0.742181 0.959312 +0.744075 0.962406 +0.737896 0.960067 +0.737384 0.963586 +0.734129 0.957892 +0.731499 0.960189 +0.732641 0.953804 +0.729175 0.953804 +0.191948 0.968733 +0.201486 0.968733 +0.201486 0.964600 +0.191948 0.964600 +0.201486 0.959901 +0.191948 0.959901 +0.201486 0.956834 +0.191948 0.956834 +0.999210 0.958446 +0.999210 0.949750 +0.994859 0.949750 +0.994859 0.958446 +0.213207 0.956217 +0.203669 0.956217 +0.203669 0.959285 +0.213207 0.959285 +0.203669 0.963984 +0.213207 0.963984 +0.203669 0.968117 +0.213207 0.968117 +0.594380 0.955474 +0.594380 0.964445 +0.598598 0.964445 +0.598598 0.955474 +0.602815 0.964445 +0.602815 0.955474 +0.789270 0.955945 +0.794037 0.960034 +0.793038 0.953770 +0.797322 0.954526 +0.800119 0.957858 +0.800119 0.962209 +0.797322 0.965542 +0.793038 0.966297 +0.789270 0.964122 +0.787782 0.960034 +0.293533 0.896429 +0.293533 0.903376 +0.297973 0.903376 +0.297973 0.896429 +0.514818 0.909237 +0.510377 0.909237 +0.514818 0.902289 +0.510377 0.902289 +0.553892 0.963786 +0.553892 0.956243 +0.549448 0.956243 +0.549448 0.963786 +0.553892 0.948700 +0.549448 0.948700 +0.668615 0.917545 +0.670753 0.930210 +0.679818 0.930210 +0.679818 0.917545 +0.327676 0.955474 +0.331567 0.948736 +0.330146 0.948437 +0.326749 0.954322 +0.328966 0.941746 +0.323761 0.937378 +0.316967 0.937378 +0.311761 0.941746 +0.309161 0.948736 +0.310582 0.948437 +0.313052 0.955474 +0.313979 0.954322 +0.320364 0.958136 +0.320364 0.956646 +0.188041 0.941660 +0.188041 0.948114 +0.189222 0.948114 +0.189222 0.941660 +0.188041 0.955454 +0.189222 0.955454 +0.188041 0.960244 +0.189222 0.960244 +0.203669 0.001931 +0.203669 0.008726 +0.204746 0.008726 +0.204746 0.001931 +0.185315 0.962485 +0.185315 0.957695 +0.184134 0.957695 +0.184134 0.962485 +0.185315 0.950355 +0.184134 0.950355 +0.185315 0.943901 +0.184134 0.943901 +0.181337 0.959136 +0.181337 0.952549 +0.180227 0.952549 +0.180227 0.959136 +0.181337 0.945962 +0.180227 0.945962 +0.029164 0.951748 +0.023280 0.948351 +0.022767 0.951869 +0.026535 0.954044 +0.016588 0.949530 +0.018483 0.952625 +0.012221 0.954735 +0.015686 0.955958 +0.012221 0.961530 +0.015686 0.960308 +0.016588 0.966735 +0.018483 0.963641 +0.023280 0.967915 +0.022767 0.964396 +0.029164 0.964518 +0.026535 0.962221 +0.031488 0.958133 +0.028023 0.958133 +0.384477 0.958202 +0.380709 0.956027 +0.379711 0.962290 +0.376425 0.956782 +0.373628 0.960115 +0.373628 0.964466 +0.376425 0.967798 +0.380709 0.968554 +0.384477 0.966379 +0.385965 0.962290 +0.215391 0.956980 +0.215391 0.961113 +0.224929 0.961113 +0.224929 0.956980 +0.215391 0.965812 +0.224929 0.965812 +0.215391 0.968880 +0.224929 0.968880 +0.954278 0.953471 +0.949927 0.953471 +0.949927 0.962167 +0.954278 0.962167 +0.236650 0.970532 +0.236650 0.967465 +0.227112 0.967465 +0.227112 0.970532 +0.236650 0.962765 +0.227112 0.962765 +0.236650 0.958632 +0.227112 0.958632 +0.668615 0.963923 +0.672833 0.963923 +0.672833 0.954953 +0.668615 0.954953 +0.677050 0.963923 +0.677050 0.954953 +0.672506 0.910806 +0.679818 0.908145 +0.691021 0.917545 +0.687130 0.910806 +0.688883 0.930210 +0.691021 0.942875 +0.687130 0.949614 +0.604943 0.954253 +0.604854 0.949903 +0.629192 0.949409 +0.629281 0.953759 +0.604766 0.945554 +0.629104 0.945060 +0.604678 0.941204 +0.629016 0.940710 +0.604589 0.936854 +0.628927 0.936360 +0.604501 0.932505 +0.628839 0.932011 +0.604413 0.928155 +0.628751 0.927661 +0.604325 0.923805 +0.628662 0.923311 +0.604236 0.919455 +0.628574 0.918961 +0.604148 0.915106 +0.628486 0.914612 +0.578563 0.942502 +0.570154 0.949521 +0.567792 0.943905 +0.572043 0.940495 +0.562307 0.916599 +0.567965 0.918408 +0.564348 0.921753 +0.560940 0.920019 +0.570922 0.923646 +0.567027 0.925328 +0.578322 0.934194 +0.572028 0.936588 +0.203669 0.063830 +0.203669 0.058380 +0.215980 0.058380 +0.215980 0.063830 +0.203669 0.067737 +0.215980 0.067737 +0.203669 0.289664 +0.215980 0.289664 +0.215980 0.300617 +0.203669 0.300617 +0.203669 0.281353 +0.215980 0.281353 +0.203669 0.262453 +0.215980 0.262453 +0.215980 0.268468 +0.203669 0.268468 +0.203669 0.256512 +0.215980 0.256512 +0.363814 0.947817 +0.368514 0.942873 +0.373891 0.943762 +0.374584 0.949815 +0.365292 0.917272 +0.368159 0.919583 +0.366038 0.922765 +0.361246 0.921621 +0.365455 0.927194 +0.361235 0.927636 +0.359954 0.940457 +0.366613 0.939459 +0.203669 0.084525 +0.215980 0.084525 +0.215980 0.088349 +0.203669 0.088349 +0.203669 0.080058 +0.215980 0.080058 +0.556723 0.917583 +0.557922 0.920435 +0.215980 0.091395 +0.203669 0.091395 +0.370642 0.915393 +0.370994 0.918466 +0.203669 0.250842 +0.215980 0.250842 +0.559256 0.950621 +0.562382 0.944559 +0.552114 0.920886 +0.555514 0.922301 +0.554370 0.925950 +0.549448 0.926195 +0.555050 0.930365 +0.551124 0.931972 +0.553487 0.944638 +0.559600 0.941814 +0.203669 0.098266 +0.203669 0.094442 +0.215980 0.094442 +0.215980 0.098266 +0.203669 0.102733 +0.215980 0.102733 +0.203669 0.212021 +0.203669 0.201067 +0.215980 0.201067 +0.215980 0.212021 +0.203669 0.220332 +0.215980 0.220332 +0.203669 0.239232 +0.203669 0.233217 +0.215980 0.233217 +0.215980 0.239232 +0.203669 0.245172 +0.215980 0.245172 +0.384623 0.945434 +0.378927 0.941681 +0.376278 0.916014 +0.381203 0.919336 +0.376793 0.921533 +0.374007 0.918913 +0.382573 0.925192 +0.378363 0.925715 +0.386720 0.937392 +0.380007 0.937925 +0.203669 0.118961 +0.215980 0.118961 +0.215980 0.124411 +0.203669 0.124411 +0.215980 0.115053 +0.203669 0.115053 +0.171656 0.960096 +0.166327 0.960097 +0.166322 0.935754 +0.171651 0.935753 +0.464449 0.942036 +0.464392 0.962543 +0.440049 0.962475 +0.440106 0.941968 +0.160696 0.960099 +0.160691 0.935756 +0.464462 0.937316 +0.440119 0.937249 +0.332630 0.921723 +0.332604 0.917004 +0.356946 0.916870 +0.356972 0.921589 +0.177288 0.960095 +0.177282 0.935752 +0.357151 0.954038 +0.332809 0.954172 +0.772183 0.896494 +0.772183 0.916984 +0.768018 0.914764 +0.766293 0.909404 +0.839767 0.918941 +0.839767 0.898451 +0.845657 0.911361 +0.843932 0.916721 +0.819260 0.918941 +0.807318 0.898451 +0.804632 0.896494 +0.792690 0.916984 +0.766293 0.904074 +0.768018 0.898714 +0.843932 0.900671 +0.845657 0.906031 +0.389257 0.934684 +0.413600 0.934684 +0.413600 0.966712 +0.389257 0.966712 +0.804632 0.949012 +0.792690 0.949012 +0.848342 0.898792 +0.872685 0.898792 +0.872685 0.951310 +0.848342 0.951310 +0.819260 0.950969 +0.807318 0.950969 +0.538021 0.930575 +0.538686 0.927543 +0.541184 0.928252 +0.540587 0.930977 +0.539713 0.924614 +0.542107 0.925619 +0.541085 0.921830 +0.543341 0.923117 +0.542784 0.919233 +0.544868 0.920783 +0.544784 0.916859 +0.546665 0.918649 +0.543613 0.950916 +0.541781 0.948410 +0.543966 0.947007 +0.545613 0.949259 +0.540265 0.945702 +0.542603 0.944573 +0.539086 0.942831 +0.541544 0.941992 +0.538264 0.939838 +0.540805 0.939302 +0.537808 0.936768 +0.540395 0.936543 +0.537727 0.933665 +0.540322 0.933754 +0.246083 0.968176 +0.248213 0.966850 +0.249051 0.967634 +0.246416 0.969275 +0.539207 0.962041 +0.534626 0.964881 +0.533820 0.962210 +0.249395 0.964636 +0.250513 0.964896 +0.534457 0.959494 +0.249312 0.962128 +0.250410 0.961794 +0.536367 0.957461 +0.247986 0.959997 +0.248770 0.959159 +0.539038 0.956655 +0.245772 0.958815 +0.246032 0.957698 +0.541753 0.957292 +0.243264 0.958899 +0.242930 0.957801 +0.543787 0.959202 +0.241133 0.960225 +0.240295 0.959441 +0.544593 0.961872 +0.239951 0.962439 +0.238833 0.962179 +0.543956 0.964588 +0.240034 0.964947 +0.238936 0.965281 +0.542046 0.966622 +0.241361 0.967078 +0.240576 0.967916 +0.539375 0.967428 +0.243575 0.968260 +0.243314 0.969378 +0.536659 0.966790 +0.420125 0.942809 +0.423184 0.942809 +0.423184 0.945507 +0.420125 0.945507 +0.420125 0.940048 +0.423184 0.940048 +0.420125 0.937320 +0.423184 0.937320 +0.420125 0.934632 +0.423184 0.934632 +0.420125 0.931983 +0.423184 0.931983 +0.420125 0.929371 +0.423184 0.929371 +0.423184 0.961581 +0.420125 0.961581 +0.420125 0.958984 +0.423184 0.958984 +0.420125 0.956391 +0.423184 0.956391 +0.420125 0.953764 +0.423184 0.953764 +0.420125 0.951084 +0.423184 0.951084 +0.420125 0.948325 +0.423184 0.948325 +0.416607 0.942809 +0.416607 0.940048 +0.416607 0.937320 +0.416607 0.934632 +0.416607 0.931983 +0.416607 0.929371 +0.416607 0.961581 +0.416607 0.958984 +0.416607 0.956391 +0.416607 0.953764 +0.416607 0.951084 +0.416607 0.948325 +0.416607 0.945507 +0.437205 0.940048 +0.437205 0.942809 +0.437205 0.937320 +0.437205 0.934632 +0.437205 0.931983 +0.437205 0.929371 +0.437205 0.958984 +0.437205 0.961581 +0.437205 0.956391 +0.437205 0.953764 +0.437205 0.951084 +0.437205 0.948325 +0.437205 0.945507 +0.516270 0.784563 +0.514284 0.784563 +0.514284 0.775256 +0.516270 0.775256 +0.514284 0.791795 +0.516270 0.791795 +0.518794 0.775256 +0.518794 0.784563 +0.518794 0.791795 +0.520996 0.784563 +0.520996 0.775256 +0.520996 0.791795 +0.523127 0.784563 +0.523127 0.775256 +0.523127 0.791795 +0.525258 0.784563 +0.525258 0.775256 +0.525258 0.791795 +0.527459 0.784563 +0.527459 0.775256 +0.527459 0.791795 +0.529984 0.784563 +0.529984 0.775256 +0.529984 0.791795 +0.531969 0.784563 +0.531969 0.775256 +0.531969 0.791795 +0.518794 0.808307 +0.516270 0.808307 +0.520996 0.808307 +0.523127 0.808307 +0.525258 0.808307 +0.527459 0.808307 +0.529984 0.808307 +0.531969 0.808307 +0.514284 0.808307 +0.940741 0.950453 +0.942525 0.950511 +0.947082 0.955140 +0.416607 0.869190 +0.416607 0.869190 +0.416607 0.874374 +0.421356 0.869190 +0.421356 0.874374 +0.100520 0.970337 +0.098740 0.970280 +0.105065 0.965721 +0.096961 0.970337 +0.092416 0.965721 +0.421356 0.914957 +0.416607 0.914957 +0.416607 0.909615 +0.421356 0.909615 +0.416607 0.914957 +0.938956 0.950511 +0.934399 0.955140 +0.421356 0.882703 +0.416607 0.882703 +0.416607 0.901224 +0.421356 0.901224 +0.421356 0.891943 +0.421356 0.895654 +0.416607 0.895654 +0.416607 0.891943 +0.416607 0.888232 +0.421356 0.888232 +0.416607 0.886613 +0.421356 0.886613 +0.421356 0.897285 +0.416607 0.897285 +0.946238 0.965812 +0.943962 0.967206 +0.940741 0.967178 +0.947182 0.962410 +0.098740 0.953602 +0.101953 0.953630 +0.104225 0.955059 +0.105164 0.958472 +0.093256 0.955059 +0.095528 0.953630 +0.092317 0.958472 +0.937519 0.967206 +0.935243 0.965812 +0.934299 0.962410 +0.516270 0.765950 +0.514284 0.765950 +0.514284 0.758718 +0.516270 0.758718 +0.518794 0.765950 +0.518794 0.758718 +0.520996 0.765950 +0.520996 0.758718 +0.523127 0.765950 +0.523127 0.758718 +0.525258 0.765950 +0.525258 0.758718 +0.527459 0.765950 +0.527459 0.758718 +0.529984 0.765950 +0.529984 0.758718 +0.531969 0.765950 +0.531969 0.758718 +0.516270 0.742206 +0.518794 0.742206 +0.520996 0.742206 +0.523127 0.742206 +0.525258 0.742206 +0.527459 0.742206 +0.529984 0.742206 +0.531969 0.742206 +0.514284 0.742206 +0.083130 0.970096 +0.089472 0.965409 +0.084914 0.970038 +0.403774 0.872610 +0.403774 0.877795 +0.403774 0.872610 +0.399025 0.877795 +0.399025 0.872610 +0.881942 0.952206 +0.886487 0.956822 +0.880162 0.952263 +0.873838 0.956822 +0.878383 0.952206 +0.399025 0.918378 +0.399025 0.913035 +0.403774 0.913035 +0.403774 0.918378 +0.403774 0.918378 +0.081345 0.970038 +0.076788 0.965409 +0.403774 0.886123 +0.399025 0.886123 +0.399025 0.904644 +0.403774 0.904644 +0.399025 0.895363 +0.403774 0.895363 +0.403774 0.899075 +0.399025 0.899075 +0.399025 0.891653 +0.403774 0.891652 +0.399025 0.890033 +0.403774 0.890033 +0.403774 0.900706 +0.399025 0.900706 +0.088627 0.954737 +0.089572 0.958139 +0.083130 0.953371 +0.086351 0.953342 +0.886586 0.964071 +0.885647 0.967484 +0.883375 0.968913 +0.880162 0.968941 +0.874678 0.967484 +0.873739 0.964071 +0.876950 0.968913 +0.076688 0.958139 +0.077633 0.954737 +0.079909 0.953342 +0.688958 0.675529 +0.689392 0.684031 +0.687708 0.684186 +0.687274 0.675638 +0.688603 0.666517 +0.686922 0.666465 +0.688575 0.658286 +0.686886 0.658005 +0.689400 0.651937 +0.687731 0.651402 +0.690251 0.724860 +0.691363 0.731171 +0.689719 0.731782 +0.688575 0.725218 +0.689909 0.716602 +0.688227 0.716750 +0.689682 0.707586 +0.688001 0.707572 +0.689735 0.699106 +0.688046 0.699029 +0.689798 0.691566 +0.688101 0.691605 +0.686246 0.684572 +0.685885 0.675875 +0.685542 0.666262 +0.685411 0.657469 +0.686141 0.650468 +0.688173 0.732788 +0.687126 0.725822 +0.686845 0.717023 +0.686616 0.707404 +0.686568 0.698712 +0.686537 0.691641 +0.684939 0.685040 +0.684716 0.676161 +0.684382 0.666001 +0.684104 0.656863 +0.684529 0.649463 +0.686609 0.733867 +0.685849 0.726490 +0.685686 0.717337 +0.685446 0.707173 +0.685241 0.698307 +0.685055 0.691676 +0.683474 0.685339 +0.683304 0.676366 +0.682992 0.665835 +0.682668 0.656449 +0.682771 0.648719 +0.684887 0.734692 +0.684434 0.726971 +0.684293 0.717572 +0.684039 0.707037 +0.683762 0.698078 +0.683532 0.691712 +0.681800 0.685455 +0.681572 0.676460 +0.681293 0.665816 +0.681055 0.656320 +0.680879 0.648490 +0.683006 0.735008 +0.682829 0.727178 +0.682591 0.717681 +0.682312 0.707038 +0.682084 0.698044 +0.681942 0.691749 +0.680122 0.685420 +0.679845 0.676461 +0.679591 0.665926 +0.679450 0.656526 +0.678998 0.648805 +0.681113 0.734779 +0.681216 0.727048 +0.680892 0.717663 +0.680580 0.707132 +0.680410 0.698159 +0.680352 0.691786 +0.678643 0.685191 +0.678438 0.676325 +0.678198 0.666160 +0.678035 0.657007 +0.677276 0.649631 +0.679355 0.734034 +0.679779 0.726635 +0.679502 0.717496 +0.679168 0.707337 +0.678945 0.698458 +0.678829 0.691822 +0.677315 0.684786 +0.677268 0.676093 +0.677039 0.666474 +0.676758 0.657675 +0.675712 0.650709 +0.677743 0.733029 +0.678472 0.726028 +0.678342 0.717236 +0.677999 0.707622 +0.677638 0.698925 +0.677347 0.691856 +0.675838 0.684468 +0.675882 0.675925 +0.675657 0.666746 +0.675310 0.658279 +0.674166 0.651715 +0.676153 0.732095 +0.676998 0.725492 +0.676962 0.717032 +0.676609 0.707859 +0.676176 0.699311 +0.675783 0.691892 +0.674149 0.684390 +0.674202 0.675910 +0.673975 0.666894 +0.673634 0.658637 +0.672522 0.652325 +0.674484 0.731560 +0.675309 0.725211 +0.675280 0.716980 +0.674925 0.707967 +0.674491 0.699465 +0.674086 0.691930 +0.298232 0.162944 +0.298232 0.303882 +0.298232 0.022007 +0.297513 0.162944 +0.428365 0.348844 +0.297513 0.304601 +0.725825 0.010936 +0.588225 0.575491 +0.725323 0.001905 +0.694515 0.010936 +0.561281 0.621776 +0.694574 0.001905 +0.427510 0.010936 +0.427837 0.001905 +0.327542 0.574172 +0.460011 0.010936 +0.459838 0.001905 +0.355583 0.622341 +0.459892 0.353449 +0.187811 0.434137 +0.459860 0.362480 +0.426164 0.353449 +0.137030 0.404575 +0.426125 0.362480 +0.727001 0.353449 +0.726814 0.362480 +0.138682 0.668066 +0.693401 0.353449 +0.693436 0.362480 +0.188925 0.638817 +</float_array> + <technique_common> + <accessor source="#MineCartEngine-UV0-array" count="3846" stride="2"> + <param name="S" type="float"/> + <param name="T" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="MineCartEngine-VERTEX"> + <input semantic="POSITION" source="#MineCartEngine-POSITION"/> + </vertices> + <triangles count="4090" material="MineCartEngine_ncl1_1"> + <input semantic="VERTEX" offset="0" source="#MineCartEngine-VERTEX"/> + <input semantic="NORMAL" offset="1" source="#MineCartEngine-Normal0"/> + <input semantic="TEXCOORD" offset="2" set="0" source="#MineCartEngine-UV0"/> + <p> 7 0 7 0 1 0 1 2 1 0 3 0 7 4 7 6 5 6 7 6 7 2 7 2 8 8 8 2 9 2 7 10 7 1 11 1 3 12 3 9 13 9 2 14 2 2 15 2 9 16 9 8 17 8 4 18 4 9 19 9 3 20 3 9 21 9 4 22 4 10 23 10 4 24 4 11 25 11 10 26 10 11 27 11 4 28 4 5 29 5 6 30 6 5 31 5 0 32 0 5 33 5 6 34 6 11 35 11 9 36 9 7 37 7 8 38 8 7 39 7 9 40 9 10 41 10 10 42 10 6 43 6 7 44 7 10 45 10 11 46 11 6 47 6 12 48 12 13 49 13 19 50 14 12 51 12 19 52 14 18 53 15 14 54 16 19 55 14 13 56 13 19 57 14 14 58 16 20 59 17 15 60 18 21 61 19 14 62 16 14 63 16 21 64 19 20 65 17 22 66 21 15 67 18 16 68 20 15 69 18 22 70 21 21 71 19 17 72 22 22 73 21 16 74 20 22 75 21 17 76 22 23 77 23 18 78 15 17 79 22 12 80 12 17 81 22 18 82 15 23 83 23 19 84 14 21 85 19 22 86 21 21 87 19 19 88 14 20 89 17 19 90 14 22 91 21 18 92 15 18 93 15 22 94 21 23 95 23 24 96 24 25 97 25 31 98 26 24 99 24 31 100 26 30 101 27 26 102 28 31 103 26 25 104 25 31 105 26 26 106 28 32 107 29 27 108 30 33 109 31 26 110 28 26 111 28 33 112 31 32 113 29 28 114 32 33 115 31 27 116 30 33 117 31 28 118 32 34 119 33 29 120 34 34 121 33 28 122 32 34 123 33 29 124 34 35 125 35 24 126 24 30 127 27 29 128 34 29 129 34 30 130 27 35 131 35 31 132 26 33 133 31 34 134 33 33 135 31 31 136 26 32 137 29 30 138 27 31 139 26 34 140 33 30 141 27 34 142 33 35 143 35 36 144 36 37 145 37 43 146 38 36 147 36 43 148 38 42 149 39 38 150 40 43 151 38 37 152 37 43 153 38 38 154 40 44 155 41 39 156 42 45 157 43 38 158 40 38 159 40 45 160 43 44 161 41 40 162 44 45 163 43 39 164 42 45 165 43 40 166 44 46 167 45 41 168 46 46 169 45 40 170 44 46 171 45 41 172 46 47 173 47 36 174 36 42 175 39 41 176 46 41 177 46 42 178 39 47 179 47 43 180 38 45 181 43 46 182 45 45 183 43 43 184 38 44 185 41 42 186 39 43 187 38 46 188 45 42 189 39 46 190 45 47 191 47 55 192 50 49 193 49 48 194 48 55 195 50 48 196 48 54 197 51 55 198 50 50 199 52 49 200 49 50 201 52 55 202 50 56 203 53 51 204 54 50 205 52 57 206 55 50 207 52 56 208 53 57 209 55 57 210 55 52 211 56 51 212 54 52 213 56 57 214 55 58 215 57 59 216 59 52 217 56 58 218 57 53 219 58 52 220 56 59 221 59 48 222 48 53 223 58 54 224 51 53 225 58 59 226 59 54 227 51 57 228 55 55 229 50 58 230 57 55 231 50 57 232 55 56 233 53 58 234 57 54 235 51 59 236 59 58 237 57 55 238 50 54 239 51 60 240 60 67 241 62 61 242 61 67 243 62 60 244 60 66 245 63 67 246 62 62 247 64 61 248 61 62 249 64 67 250 62 68 251 65 63 252 66 62 253 64 69 254 67 62 255 64 68 256 65 69 257 67 70 258 69 63 259 66 69 260 67 63 261 66 70 262 69 64 263 68 70 264 69 65 265 70 64 266 68 65 267 70 70 268 69 71 269 71 60 270 60 65 271 70 66 272 63 65 273 70 71 274 71 66 275 63 69 276 67 67 277 62 70 278 69 67 279 62 69 280 67 68 281 65 66 282 63 71 283 71 70 284 69 66 285 63 70 286 69 67 287 62 72 288 72 79 289 74 73 290 73 79 291 74 72 292 72 78 293 75 79 294 74 74 295 76 73 296 73 74 297 76 79 298 74 80 299 77 75 300 78 74 301 76 81 302 79 74 303 76 80 304 77 81 305 79 81 306 79 76 307 80 75 308 78 76 309 80 81 310 79 82 311 81 77 312 82 82 313 81 83 314 83 82 315 81 77 316 82 76 317 80 72 318 72 77 319 82 78 320 75 77 321 82 83 322 83 78 323 75 81 324 79 79 325 74 82 326 81 79 327 74 81 328 79 80 329 77 82 330 81 78 331 75 83 332 83 78 333 75 82 334 81 79 335 74 84 336 84 91 337 86 85 338 85 91 339 86 84 340 84 90 341 87 91 342 86 86 343 88 85 344 85 86 345 88 91 346 86 92 347 89 87 348 90 86 349 88 93 350 91 86 351 88 92 352 89 93 353 91 93 354 91 88 355 92 87 356 90 88 357 92 93 358 91 94 359 93 89 360 94 94 361 93 95 362 95 94 363 93 89 364 94 88 365 92 84 366 84 89 367 94 90 368 87 89 369 94 95 370 95 90 371 87 93 372 91 91 373 86 94 374 93 91 375 86 93 376 91 92 377 89 94 378 93 90 379 87 95 380 95 90 381 87 94 382 93 91 383 86 103 384 98 97 385 97 96 386 96 103 387 98 96 388 96 102 389 99 103 390 98 98 391 100 97 392 97 98 393 100 103 394 98 104 395 101 99 396 102 98 397 100 105 398 103 98 399 100 104 400 101 105 401 103 100 402 104 105 403 103 106 404 105 105 405 103 100 406 104 99 407 102 100 408 104 107 409 107 101 410 106 107 411 107 100 412 104 106 413 105 96 414 96 101 415 106 102 416 99 101 417 106 107 418 107 102 419 99 105 420 103 103 421 98 106 422 105 103 423 98 105 424 103 104 425 101 106 426 105 102 427 99 107 428 107 106 429 105 103 430 98 102 431 99 108 432 108 115 433 110 109 434 109 115 435 110 108 436 108 114 437 111 115 438 110 110 439 112 109 440 109 110 441 112 115 442 110 116 443 113 111 444 114 110 445 112 117 446 115 110 447 112 116 448 113 117 449 115 118 450 117 112 451 116 111 452 114 118 453 117 111 454 114 117 455 115 118 456 117 113 457 118 112 458 116 113 459 118 118 460 117 119 461 119 108 462 108 113 463 118 114 464 111 113 465 118 119 466 119 114 467 111 117 468 115 115 469 110 118 470 117 115 471 110 117 472 115 116 473 113 114 474 111 119 475 119 118 476 117 114 477 111 118 478 117 115 479 110 120 480 120 127 481 122 121 482 121 127 483 122 120 484 120 126 485 123 127 486 122 122 487 124 121 488 121 122 489 124 127 490 122 128 491 125 123 492 126 122 493 124 129 494 127 122 495 124 128 496 125 129 497 127 124 498 128 129 499 127 130 500 129 129 501 127 124 502 128 123 503 126 125 504 130 130 505 129 131 506 131 130 507 129 125 508 130 124 509 128 120 510 120 125 511 130 126 512 123 125 513 130 131 514 131 126 515 123 129 516 127 127 517 122 130 518 129 127 519 122 129 520 127 128 521 125 130 522 129 126 523 123 131 524 131 126 525 123 130 526 129 127 527 122 132 528 132 139 529 134 133 530 133 139 531 134 132 532 132 138 533 135 139 534 134 134 535 136 133 536 133 134 537 136 139 538 134 140 539 137 135 540 138 134 541 136 141 542 139 134 543 136 140 544 137 141 545 139 136 546 140 141 547 139 142 548 141 141 549 139 136 550 140 135 551 138 137 552 142 142 553 141 143 554 143 142 555 141 137 556 142 136 557 140 132 558 132 137 559 142 138 560 135 137 561 142 143 562 143 138 563 135 141 564 139 139 565 134 142 566 141 139 567 134 141 568 139 140 569 137 142 570 141 138 571 135 143 572 143 138 573 135 142 574 141 139 575 134 151 576 146 144 577 144 145 578 147 144 579 144 151 580 146 150 581 145 151 582 146 146 583 149 152 584 148 146 585 149 151 586 146 145 587 147 147 588 151 153 589 150 146 590 149 146 591 149 153 592 150 152 593 148 153 594 150 148 595 153 154 596 152 148 597 153 153 598 150 147 599 151 149 600 155 155 601 154 148 602 153 148 603 153 155 604 154 154 605 152 150 606 145 149 607 155 144 608 144 149 609 155 150 610 145 155 611 154 153 612 150 151 613 146 152 614 148 151 615 146 153 616 150 154 617 152 154 618 152 150 619 145 151 620 146 154 621 152 155 622 154 150 623 145 156 624 156 157 625 159 163 626 158 156 627 156 163 628 158 162 629 157 158 630 161 163 631 158 157 632 159 163 633 158 158 634 161 164 635 160 159 636 163 165 637 162 158 638 161 158 639 161 165 640 162 164 641 160 165 642 162 159 643 163 166 644 164 159 645 163 160 646 165 166 647 164 161 648 167 166 649 164 160 650 165 166 651 164 161 652 167 167 653 166 162 654 157 161 655 167 156 656 156 161 657 167 162 658 157 167 659 166 163 660 158 165 661 162 166 662 164 165 663 162 163 664 158 164 665 160 163 666 158 166 667 164 162 668 157 162 669 157 166 670 164 167 671 166 168 672 168 169 673 171 175 674 170 168 675 168 175 676 170 174 677 169 170 678 173 175 679 170 169 680 171 175 681 170 170 682 173 176 683 172 171 684 175 177 685 174 170 686 173 170 687 173 177 688 174 176 689 172 177 690 174 172 691 177 178 692 176 172 693 177 177 694 174 171 695 175 173 696 179 178 697 176 172 698 177 178 699 176 173 700 179 179 701 178 168 702 168 174 703 169 173 704 179 173 705 179 174 706 169 179 707 178 175 708 170 177 709 174 178 710 176 177 711 174 175 712 170 176 713 172 174 714 169 175 715 170 178 716 176 174 717 169 178 718 176 179 719 178 180 720 180 181 721 183 187 722 182 180 723 180 187 724 182 186 725 181 182 726 185 187 727 182 181 728 183 187 729 182 182 730 185 188 731 184 183 732 187 189 733 186 182 734 185 182 735 185 189 736 186 188 737 184 189 738 186 184 739 189 190 740 188 184 741 189 189 742 186 183 743 187 185 744 191 190 745 188 184 746 189 190 747 188 185 748 191 191 749 190 180 750 180 186 751 181 185 752 191 185 753 191 186 754 181 191 755 190 187 756 182 189 757 186 190 758 188 189 759 186 187 760 182 188 761 184 186 762 181 187 763 182 190 764 188 186 765 181 190 766 188 191 767 190 199 768 194 192 769 192 193 770 193 192 771 192 199 772 194 198 773 195 200 774 197 199 775 194 193 776 193 200 777 197 193 778 193 194 779 196 200 780 197 194 781 196 201 782 199 194 783 196 195 784 198 201 785 199 201 786 203 195 787 200 202 788 202 195 789 200 196 790 201 202 791 202 197 792 204 203 793 205 196 794 201 196 795 201 203 796 205 202 797 202 198 798 195 197 799 204 192 800 192 197 801 204 198 802 195 203 803 205 198 804 206 199 805 207 204 806 208 199 807 207 200 808 209 204 809 208 200 810 209 201 811 210 204 812 208 201 813 210 202 814 211 204 815 208 202 816 211 203 817 212 204 818 208 203 819 212 198 820 206 204 821 208 212 822 215 205 823 213 206 824 214 205 825 213 212 826 215 211 827 216 213 828 218 212 829 215 206 830 214 213 831 218 206 832 214 207 833 217 214 834 220 213 835 218 207 836 217 214 837 220 207 838 217 208 839 219 214 840 224 208 841 221 215 842 223 208 843 221 209 844 222 215 845 223 210 846 225 216 847 226 209 848 222 209 849 222 216 850 226 215 851 223 205 852 213 211 853 216 210 854 225 210 855 225 211 856 216 216 857 226 211 858 227 212 859 228 217 860 229 212 861 228 213 862 230 217 863 229 213 864 230 214 865 231 217 866 229 214 867 231 215 868 232 217 869 229 215 870 232 216 871 233 217 872 229 216 873 233 211 874 227 217 875 229 225 876 236 219 877 237 218 878 234 225 879 236 218 880 234 224 881 235 226 882 240 219 883 238 225 884 239 219 885 238 226 886 240 220 887 241 227 888 242 220 889 241 226 890 240 220 891 241 227 892 242 221 893 243 227 894 242 228 895 244 221 896 243 221 897 243 228 898 244 222 899 245 223 900 247 222 901 245 229 902 246 222 903 245 228 904 244 229 905 246 224 906 235 218 907 234 223 908 247 224 909 235 223 910 247 229 911 246 224 912 248 230 913 249 225 914 250 225 915 250 230 916 249 226 917 251 226 918 251 230 919 249 227 920 252 227 921 252 230 922 249 228 923 253 228 924 253 230 925 249 229 926 254 229 927 254 230 928 249 224 929 248 238 930 257 232 931 258 231 932 255 238 933 257 231 934 255 237 935 256 239 936 261 232 937 259 238 938 260 232 939 259 239 940 261 233 941 262 240 942 263 233 943 262 239 944 261 233 945 262 240 946 263 234 947 264 240 948 263 241 949 265 234 950 264 234 951 264 241 952 265 235 953 266 236 954 268 235 955 266 242 956 267 235 957 266 241 958 265 242 959 267 231 960 255 236 961 268 237 962 256 236 963 268 242 964 267 237 965 256 237 966 269 243 967 270 238 968 271 238 969 271 243 970 270 239 971 272 239 972 272 243 973 270 240 974 273 240 975 273 243 976 270 241 977 274 241 978 274 243 979 270 242 980 275 242 981 275 243 982 270 237 983 269 245 984 277 247 985 278 244 986 276 244 987 276 247 988 278 246 989 279 253 990 281 254 991 283 252 992 280 254 993 283 253 994 281 255 995 282 258 996 286 253 997 284 252 998 285 253 999 284 258 1000 286 259 1001 287 255 1002 289 256 1003 291 254 1004 288 256 1005 291 255 1006 289 257 1007 290 259 1008 294 256 1009 292 257 1010 293 256 1011 292 259 1012 294 258 1013 295 244 1014 297 254 1015 283 245 1016 296 254 1017 283 244 1018 297 252 1019 280 247 1020 299 256 1021 292 246 1022 298 258 1023 295 246 1024 298 256 1025 292 245 1026 301 256 1027 291 247 1028 300 256 1029 291 245 1030 301 254 1031 288 248 1032 304 260 1033 305 266 1034 302 248 1035 304 266 1036 302 249 1037 303 249 1038 307 269 1039 309 250 1040 306 269 1041 309 249 1042 307 266 1043 308 269 1044 313 251 1045 311 250 1046 312 251 1047 311 269 1048 313 263 1049 310 260 1050 314 248 1051 315 251 1052 316 260 1053 314 251 1054 316 263 1055 317 271 1056 319 257 1057 293 265 1058 318 257 1059 293 271 1060 319 259 1061 294 262 1062 320 257 1063 290 255 1064 289 257 1065 290 262 1066 320 265 1067 321 268 1068 322 255 1069 282 253 1070 281 255 1071 282 268 1072 322 262 1073 323 271 1074 324 268 1075 325 253 1076 284 253 1077 284 259 1078 287 271 1079 324 267 1080 327 260 1081 305 261 1082 326 260 1083 305 267 1084 327 266 1085 302 267 1086 327 262 1087 323 268 1088 322 262 1089 323 267 1090 327 261 1091 326 261 1092 328 265 1093 321 262 1094 320 265 1095 321 261 1096 328 264 1097 329 260 1098 314 263 1099 317 261 1100 328 261 1101 328 263 1102 317 264 1103 329 267 1104 330 270 1105 331 266 1106 308 266 1107 308 270 1108 331 269 1109 309 268 1110 325 270 1111 331 267 1112 330 270 1113 331 268 1114 325 271 1115 324 265 1116 318 264 1117 332 270 1118 333 265 1119 318 270 1120 333 271 1121 319 270 1122 333 263 1123 310 269 1124 313 263 1125 310 270 1126 333 264 1127 332 275 1128 336 273 1129 337 272 1130 334 272 1131 334 274 1132 335 275 1133 336 278 1134 339 277 1135 341 276 1136 338 277 1137 341 278 1138 339 279 1139 340 282 1140 344 276 1141 345 277 1142 342 277 1143 342 283 1144 343 282 1145 344 279 1146 349 280 1147 347 281 1148 348 280 1149 347 279 1150 349 278 1151 346 283 1152 352 281 1153 353 280 1154 350 280 1155 350 282 1156 351 283 1157 352 278 1158 339 272 1159 354 273 1160 355 272 1161 354 278 1162 339 276 1163 338 274 1164 356 282 1165 351 280 1166 350 274 1167 356 280 1168 350 275 1169 357 273 1170 358 280 1171 347 278 1172 346 280 1173 347 273 1174 358 275 1175 359 284 1176 361 248 1177 304 290 1178 360 290 1179 360 248 1180 304 249 1181 303 249 1182 307 293 1183 362 290 1184 363 293 1185 362 249 1186 307 250 1187 306 251 1188 311 293 1189 365 250 1190 312 293 1191 365 251 1192 311 287 1193 364 287 1194 367 251 1195 316 284 1196 366 248 1197 315 284 1198 366 251 1199 316 281 1200 353 295 1201 368 289 1202 369 295 1203 368 281 1204 353 283 1205 352 279 1206 349 281 1207 348 286 1208 371 286 1209 371 281 1210 348 289 1211 370 292 1212 373 277 1213 341 279 1214 340 279 1215 340 286 1216 372 292 1217 373 292 1218 374 295 1219 375 277 1220 342 277 1221 342 295 1222 375 283 1223 343 285 1224 377 284 1225 361 291 1226 376 284 1227 361 290 1228 360 291 1229 376 286 1230 372 291 1231 376 292 1232 373 291 1233 376 286 1234 372 285 1235 377 285 1236 379 289 1237 370 288 1238 378 289 1239 370 285 1240 379 286 1241 371 287 1242 367 284 1243 366 285 1244 379 285 1245 379 288 1246 378 287 1247 367 294 1248 380 291 1249 381 290 1250 363 290 1251 363 293 1252 362 294 1253 380 292 1254 374 294 1255 380 295 1256 375 294 1257 380 292 1258 374 291 1259 381 295 1260 368 294 1261 382 289 1262 369 288 1263 383 289 1264 369 294 1265 382 287 1266 364 294 1267 382 293 1268 365 294 1269 382 287 1270 364 288 1271 383 317 1272 386 296 1273 384 297 1274 385 296 1275 384 317 1276 386 316 1277 387 318 1278 389 297 1279 385 298 1280 388 297 1281 385 318 1282 389 317 1283 386 299 1284 390 318 1285 389 298 1286 388 318 1287 389 299 1288 390 319 1289 391 300 1290 392 319 1291 391 299 1292 390 319 1293 391 300 1294 392 320 1295 393 321 1296 395 300 1297 392 301 1298 394 300 1299 392 321 1300 395 320 1301 393 322 1302 397 301 1303 394 302 1304 396 301 1305 394 322 1306 397 321 1307 395 323 1308 399 302 1309 396 303 1310 398 302 1311 396 323 1312 399 322 1313 397 324 1314 401 303 1315 398 304 1316 400 303 1317 398 324 1318 401 323 1319 399 325 1320 403 304 1321 400 305 1322 402 304 1323 400 325 1324 403 324 1325 401 326 1326 405 305 1327 402 306 1328 404 305 1329 402 326 1330 405 325 1331 403 327 1332 407 306 1333 404 307 1334 406 306 1335 404 327 1336 407 326 1337 405 328 1338 409 307 1339 406 308 1340 408 307 1341 406 328 1342 409 327 1343 407 329 1344 411 328 1345 409 308 1346 408 308 1347 408 309 1348 410 329 1349 411 330 1350 413 329 1351 411 309 1352 410 309 1353 410 310 1354 412 330 1355 413 331 1356 415 330 1357 413 310 1358 412 310 1359 412 311 1360 414 331 1361 415 331 1362 415 312 1363 416 332 1364 417 312 1365 416 331 1366 415 311 1367 414 333 1368 419 312 1369 416 313 1370 418 312 1371 416 333 1372 419 332 1373 417 334 1374 421 313 1375 418 314 1376 420 313 1377 418 334 1378 421 333 1379 419 335 1380 423 314 1381 420 315 1382 422 314 1383 420 335 1384 423 334 1385 421 296 1386 424 335 1387 423 315 1388 422 335 1389 423 296 1390 424 316 1391 425 336 1392 429 317 1393 427 337 1394 428 317 1395 427 336 1396 429 316 1397 426 318 1398 430 337 1399 428 317 1400 427 337 1401 428 318 1402 430 338 1403 431 319 1404 432 338 1405 431 318 1406 430 338 1407 431 319 1408 432 339 1409 433 320 1410 434 339 1411 433 319 1412 432 339 1413 433 320 1414 434 340 1415 435 340 1416 435 321 1417 436 341 1418 437 321 1419 436 340 1420 435 320 1421 434 321 1422 436 342 1423 439 341 1424 437 342 1425 439 321 1426 436 322 1427 438 342 1428 439 323 1429 440 343 1430 441 323 1431 440 342 1432 439 322 1433 438 344 1434 443 343 1435 441 323 1436 440 323 1437 440 324 1438 442 344 1439 443 324 1440 442 325 1441 444 345 1442 445 324 1443 442 345 1444 445 344 1445 443 326 1446 446 345 1447 445 325 1448 444 345 1449 445 326 1450 446 346 1451 447 327 1452 448 346 1453 447 326 1454 446 346 1455 447 327 1456 448 347 1457 449 327 1458 448 348 1459 451 347 1460 449 348 1461 451 327 1462 448 328 1463 450 349 1464 453 348 1465 451 328 1466 450 328 1467 450 329 1468 452 349 1469 453 350 1470 455 349 1471 453 329 1472 452 329 1473 452 330 1474 454 350 1475 455 330 1476 454 331 1477 456 351 1478 457 330 1479 454 351 1480 457 350 1481 455 331 1482 456 332 1483 458 352 1484 459 331 1485 456 352 1486 459 351 1487 457 353 1488 461 332 1489 458 333 1490 460 332 1491 458 353 1492 461 352 1493 459 354 1494 463 333 1495 460 334 1496 462 333 1497 460 354 1498 463 353 1499 461 334 1500 462 355 1501 465 354 1502 463 355 1503 465 334 1504 462 335 1505 464 355 1506 465 316 1507 426 336 1508 429 316 1509 426 355 1510 465 335 1511 464 377 1512 467 414 1513 468 376 1514 466 376 1515 466 414 1516 468 415 1517 469 379 1518 470 377 1519 467 376 1520 466 377 1521 467 379 1522 470 378 1523 471 381 1524 472 378 1525 471 379 1526 470 378 1527 471 381 1528 472 380 1529 473 381 1530 472 383 1531 474 380 1532 473 380 1533 473 383 1534 474 382 1535 475 385 1536 476 382 1537 475 383 1538 474 382 1539 475 385 1540 476 384 1541 477 387 1542 478 384 1543 477 385 1544 476 384 1545 477 387 1546 478 386 1547 479 387 1548 478 389 1549 480 386 1550 479 386 1551 479 389 1552 480 388 1553 481 391 1554 482 388 1555 481 389 1556 480 388 1557 481 391 1558 482 390 1559 483 391 1560 482 393 1561 484 390 1562 483 390 1563 483 393 1564 484 392 1565 485 395 1566 486 392 1567 485 393 1568 484 392 1569 485 395 1570 486 394 1571 487 397 1572 488 394 1573 487 395 1574 486 394 1575 487 397 1576 488 396 1577 489 397 1578 488 399 1579 490 396 1580 489 396 1581 489 399 1582 490 398 1583 491 399 1584 490 401 1585 492 398 1586 491 398 1587 491 401 1588 492 400 1589 493 401 1590 495 402 1591 497 400 1592 494 402 1593 497 401 1594 495 403 1595 496 403 1596 496 404 1597 499 402 1598 497 404 1599 499 403 1600 496 405 1601 498 405 1602 498 407 1603 500 404 1604 499 404 1605 499 407 1606 500 406 1607 501 408 1608 503 407 1609 500 409 1610 502 407 1611 500 408 1612 503 406 1613 501 410 1614 505 409 1615 502 411 1616 504 409 1617 502 410 1618 505 408 1619 503 413 1620 506 412 1621 507 410 1622 505 413 1623 506 410 1624 505 411 1625 504 415 1626 469 414 1627 468 412 1628 507 415 1629 469 412 1630 507 413 1631 506 396 1632 489 336 1633 508 337 1634 509 336 1635 508 396 1636 489 398 1637 491 338 1638 510 396 1639 489 337 1640 509 396 1641 489 338 1642 510 394 1643 487 339 1644 511 394 1645 487 338 1646 510 394 1647 487 339 1648 511 392 1649 485 340 1650 512 392 1651 485 339 1652 511 392 1653 485 340 1654 512 390 1655 483 388 1656 481 340 1657 512 341 1658 513 340 1659 512 388 1660 481 390 1661 483 386 1662 479 341 1663 513 342 1664 514 341 1665 513 386 1666 479 388 1667 481 343 1668 515 386 1669 479 342 1670 514 386 1671 479 343 1672 515 384 1673 477 344 1674 516 384 1675 477 343 1676 515 384 1677 477 344 1678 516 382 1679 475 345 1680 517 382 1681 475 344 1682 516 382 1683 475 345 1684 517 380 1685 473 378 1686 471 345 1687 517 346 1688 518 345 1689 517 378 1690 471 380 1691 473 377 1692 467 346 1693 518 347 1694 519 346 1695 518 377 1696 467 378 1697 471 377 1698 467 348 1699 520 414 1700 468 348 1701 520 377 1702 467 347 1703 519 414 1704 468 349 1705 521 412 1706 507 349 1707 521 414 1708 468 348 1709 520 412 1710 507 350 1711 522 410 1712 505 350 1713 522 412 1714 507 349 1715 521 408 1716 503 410 1717 505 350 1718 522 350 1719 522 351 1720 523 408 1721 503 406 1722 501 408 1723 503 351 1724 523 351 1725 523 352 1726 524 406 1727 501 406 1728 501 352 1729 524 404 1730 499 352 1731 524 353 1732 525 404 1733 499 354 1734 526 404 1735 499 353 1736 525 404 1737 499 354 1738 526 402 1739 497 355 1740 527 402 1741 497 354 1742 526 402 1743 497 355 1744 527 400 1745 494 398 1746 491 355 1747 528 336 1748 508 355 1749 528 398 1750 491 400 1751 493 367 1752 530 366 1753 529 376 1754 466 376 1755 466 366 1756 529 379 1757 470 379 1758 470 365 1759 531 381 1760 472 365 1761 531 379 1762 470 366 1763 529 365 1764 531 383 1765 474 381 1766 472 383 1767 474 365 1768 531 364 1769 532 364 1770 532 385 1771 476 383 1772 474 385 1773 476 364 1774 532 363 1775 533 363 1776 533 387 1777 478 385 1778 476 387 1779 478 363 1780 533 362 1781 534 387 1782 478 361 1783 535 389 1784 480 361 1785 535 387 1786 478 362 1787 534 389 1788 480 360 1789 536 391 1790 482 360 1791 536 389 1792 480 361 1793 535 360 1794 536 393 1795 484 391 1796 482 393 1797 484 360 1798 536 359 1799 537 359 1800 537 395 1801 486 393 1802 484 395 1803 486 359 1804 537 358 1805 538 358 1806 538 397 1807 488 395 1808 486 397 1809 488 358 1810 538 357 1811 539 397 1812 488 356 1813 540 399 1814 490 356 1815 540 397 1816 488 357 1817 539 399 1818 490 375 1819 541 401 1820 492 375 1821 541 399 1822 490 356 1823 540 375 1824 542 403 1825 496 401 1826 495 403 1827 496 375 1828 542 374 1829 543 374 1830 543 405 1831 498 403 1832 496 405 1833 498 374 1834 543 373 1835 544 372 1836 545 405 1837 498 373 1838 544 405 1839 498 372 1840 545 407 1841 500 371 1842 546 407 1843 500 372 1844 545 407 1845 500 371 1846 546 409 1847 502 370 1848 547 409 1849 502 371 1850 546 409 1851 502 370 1852 547 411 1853 504 370 1854 547 369 1855 548 413 1856 506 413 1857 506 411 1858 504 370 1859 547 369 1860 548 368 1861 549 415 1862 469 415 1863 469 413 1864 506 369 1865 548 367 1866 530 376 1867 466 368 1868 549 376 1869 466 415 1870 469 368 1871 549 456 1872 553 417 1873 551 418 1874 552 417 1875 551 456 1876 553 455 1877 550 418 1878 552 419 1879 554 420 1880 555 419 1881 554 418 1882 552 417 1883 551 422 1884 557 420 1885 555 419 1886 554 419 1887 554 421 1888 556 422 1889 557 423 1890 558 422 1891 557 421 1892 556 422 1893 557 423 1894 558 424 1895 559 425 1896 560 424 1897 559 423 1898 558 424 1899 559 425 1900 560 426 1901 561 425 1902 560 428 1903 563 426 1904 561 428 1905 563 425 1906 560 427 1907 562 428 1908 563 429 1909 564 430 1910 565 429 1911 564 428 1912 563 427 1913 562 430 1914 565 431 1915 566 432 1916 567 431 1917 566 430 1918 565 429 1919 564 431 1920 566 433 1921 568 432 1922 567 432 1923 567 433 1924 568 434 1925 569 434 1926 569 435 1927 570 436 1928 571 435 1929 570 434 1930 569 433 1931 568 438 1932 573 435 1933 570 437 1934 572 435 1935 570 438 1936 573 436 1937 571 439 1938 574 438 1939 573 437 1940 572 438 1941 573 439 1942 574 440 1943 575 440 1944 575 441 1945 576 442 1946 577 441 1947 576 440 1948 575 439 1949 574 444 1950 579 442 1951 577 441 1952 576 444 1953 579 441 1954 576 443 1955 578 446 1956 581 444 1957 579 443 1958 578 443 1959 578 445 1960 580 446 1961 581 448 1962 583 446 1963 581 445 1964 580 445 1965 580 447 1966 582 448 1967 583 449 1968 584 448 1969 583 447 1970 582 448 1971 583 449 1972 584 450 1973 585 452 1974 587 449 1975 584 451 1976 586 449 1977 584 452 1978 587 450 1979 585 451 1980 586 454 1981 589 452 1982 587 454 1983 589 451 1984 586 453 1985 588 453 1986 588 456 1987 553 454 1988 589 456 1989 553 453 1990 588 455 1991 550 417 1992 551 357 1993 591 419 1994 554 357 1995 591 417 1996 551 356 1997 590 357 1998 591 358 1999 592 421 2000 556 357 2001 591 421 2002 556 419 2003 554 359 2004 593 421 2005 556 358 2006 592 421 2007 556 359 2008 593 423 2009 558 360 2010 594 423 2011 558 359 2012 593 423 2013 558 360 2014 594 425 2015 560 425 2016 560 361 2017 595 427 2018 562 361 2019 595 425 2020 560 360 2021 594 427 2022 562 362 2023 596 429 2024 564 362 2025 596 427 2026 562 361 2027 595 429 2028 564 363 2029 597 431 2030 566 363 2031 597 429 2032 564 362 2033 596 431 2034 566 364 2035 598 433 2036 568 364 2037 598 431 2038 566 363 2039 597 364 2040 598 365 2041 599 435 2042 570 364 2043 598 435 2044 570 433 2045 568 437 2046 572 365 2047 599 366 2048 600 365 2049 599 437 2050 572 435 2051 570 439 2052 574 366 2053 600 367 2054 601 366 2055 600 439 2056 574 437 2057 572 367 2058 601 441 2059 576 439 2060 574 441 2061 576 367 2062 601 368 2063 602 443 2064 578 441 2065 576 368 2066 602 368 2067 602 369 2068 603 443 2069 578 445 2070 580 443 2071 578 369 2072 603 369 2073 603 370 2074 604 445 2075 580 370 2076 604 371 2077 605 447 2078 582 370 2079 604 447 2080 582 445 2081 580 371 2082 605 372 2083 606 449 2084 584 371 2085 605 449 2086 584 447 2087 582 373 2088 607 449 2089 584 372 2090 606 449 2091 584 373 2092 607 451 2093 586 374 2094 608 451 2095 586 373 2096 607 451 2097 586 374 2098 608 453 2099 588 374 2100 608 455 2101 550 453 2102 588 455 2103 550 374 2104 608 375 2105 609 455 2106 550 356 2107 590 417 2108 551 356 2109 590 455 2110 550 375 2111 609 418 2112 552 420 2113 555 416 2114 610 420 2115 555 422 2116 557 416 2117 610 422 2118 557 424 2119 559 416 2120 610 424 2121 559 426 2122 561 416 2123 610 426 2124 561 428 2125 563 416 2126 610 428 2127 563 430 2128 565 416 2129 610 430 2130 565 432 2131 567 416 2132 610 432 2133 567 434 2134 569 416 2135 610 434 2136 569 436 2137 571 416 2138 610 436 2139 571 438 2140 573 416 2141 610 438 2142 573 440 2143 575 416 2144 610 440 2145 575 442 2146 577 416 2147 610 442 2148 577 444 2149 579 416 2150 610 444 2151 579 446 2152 581 416 2153 610 446 2154 581 448 2155 583 416 2156 610 448 2157 583 450 2158 585 416 2159 610 450 2160 585 452 2161 587 416 2162 610 452 2163 587 454 2164 589 416 2165 610 454 2166 589 456 2167 553 416 2168 610 456 2169 553 418 2170 552 416 2171 610 477 2172 612 478 2173 613 457 2174 611 457 2175 611 478 2176 613 458 2177 614 479 2178 615 459 2179 616 458 2180 614 479 2181 615 458 2182 614 478 2183 613 460 2184 618 479 2185 615 480 2186 617 479 2187 615 460 2188 618 459 2189 616 461 2190 620 480 2191 617 481 2192 619 480 2193 617 461 2194 620 460 2195 618 462 2196 622 461 2197 620 482 2198 621 482 2199 621 461 2200 620 481 2201 619 463 2202 624 462 2203 622 483 2204 623 483 2205 623 462 2206 622 482 2207 621 483 2208 623 464 2209 626 463 2210 624 464 2211 626 483 2212 623 484 2213 625 484 2214 625 485 2215 627 464 2216 626 464 2217 626 485 2218 627 465 2219 628 486 2220 629 465 2221 628 485 2222 627 465 2223 628 486 2224 629 466 2225 630 486 2226 629 487 2227 631 466 2228 630 466 2229 630 487 2230 631 467 2231 632 487 2232 631 488 2233 633 467 2234 632 467 2235 632 488 2236 633 468 2237 634 488 2238 633 489 2239 635 468 2240 634 468 2241 634 489 2242 635 469 2243 636 490 2244 637 469 2245 636 489 2246 635 469 2247 636 490 2248 637 470 2249 638 490 2250 637 491 2251 639 470 2252 638 470 2253 638 491 2254 639 471 2255 640 491 2256 639 492 2257 641 471 2258 640 471 2259 640 492 2260 641 472 2261 642 492 2262 641 473 2263 644 472 2264 642 473 2265 644 492 2266 641 493 2267 643 493 2268 643 494 2269 645 473 2270 644 473 2271 644 494 2272 645 474 2273 646 494 2274 645 495 2275 647 474 2276 646 474 2277 646 495 2278 647 475 2279 648 495 2280 647 496 2281 649 475 2282 648 475 2283 648 496 2284 649 476 2285 650 496 2286 649 457 2287 652 476 2288 650 457 2289 652 496 2290 649 477 2291 651 497 2292 654 478 2293 656 477 2294 653 478 2295 656 497 2296 654 498 2297 655 498 2298 655 479 2299 658 478 2300 656 479 2301 658 498 2302 655 499 2303 657 499 2304 657 480 2305 660 479 2306 658 480 2307 660 499 2308 657 500 2309 659 481 2310 662 500 2311 659 501 2312 661 500 2313 659 481 2314 662 480 2315 660 482 2316 664 501 2317 661 502 2318 663 501 2319 661 482 2320 664 481 2321 662 482 2322 664 503 2323 665 483 2324 666 503 2325 665 482 2326 664 502 2327 663 503 2328 665 484 2329 668 483 2330 666 484 2331 668 503 2332 665 504 2333 667 505 2334 669 484 2335 668 504 2336 667 484 2337 668 505 2338 669 485 2339 670 505 2340 669 506 2341 671 485 2342 670 486 2343 672 485 2344 670 506 2345 671 487 2346 674 506 2347 671 507 2348 673 506 2349 671 487 2350 674 486 2351 672 488 2352 676 507 2353 673 508 2354 675 507 2355 673 488 2356 676 487 2357 674 488 2358 676 509 2359 677 489 2360 678 509 2361 677 488 2362 676 508 2363 675 510 2364 679 489 2365 678 509 2366 677 489 2367 678 510 2368 679 490 2369 680 511 2370 681 490 2371 680 510 2372 679 490 2373 680 511 2374 681 491 2375 682 512 2376 683 491 2377 682 511 2378 681 491 2379 682 512 2380 683 492 2381 684 512 2382 683 513 2383 685 492 2384 684 493 2385 686 492 2386 684 513 2387 685 494 2388 688 493 2389 686 514 2390 687 493 2391 686 513 2392 685 514 2393 687 495 2394 690 514 2395 687 515 2396 689 514 2397 687 495 2398 690 494 2399 688 495 2400 690 516 2401 691 496 2402 692 516 2403 691 495 2404 690 515 2405 689 516 2406 691 477 2407 653 496 2408 692 477 2409 653 516 2410 691 497 2411 654 538 2412 696 537 2413 693 575 2414 695 537 2415 693 576 2416 694 575 2417 695 540 2418 698 538 2419 696 539 2420 697 538 2421 696 540 2422 698 537 2423 693 542 2424 700 539 2425 697 541 2426 699 539 2427 697 542 2428 700 540 2429 698 544 2430 702 541 2431 699 543 2432 701 541 2433 699 544 2434 702 542 2435 700 546 2436 704 543 2437 701 545 2438 703 543 2439 701 546 2440 704 544 2441 702 548 2442 706 545 2443 703 547 2444 705 545 2445 703 548 2446 706 546 2447 704 548 2448 706 547 2449 705 550 2450 708 547 2451 705 549 2452 707 550 2453 708 550 2454 708 549 2455 707 552 2456 710 549 2457 707 551 2458 709 552 2459 710 552 2460 710 551 2461 709 554 2462 712 551 2463 709 553 2464 711 554 2465 712 554 2466 712 553 2467 711 556 2468 714 553 2469 711 555 2470 713 556 2471 714 556 2472 714 555 2473 713 558 2474 716 555 2475 713 557 2476 715 558 2477 716 560 2478 718 557 2479 715 559 2480 717 557 2481 715 560 2482 718 558 2483 716 562 2484 720 559 2485 717 561 2486 719 559 2487 717 562 2488 720 560 2489 718 563 2490 722 562 2491 724 561 2492 721 562 2493 724 563 2494 722 564 2495 723 565 2496 725 564 2497 723 563 2498 722 564 2499 723 565 2500 725 566 2501 726 567 2502 727 566 2503 726 565 2504 725 566 2505 726 567 2506 727 568 2507 728 569 2508 729 568 2509 728 567 2510 727 568 2511 728 569 2512 729 570 2513 730 571 2514 731 570 2515 730 569 2516 729 570 2517 730 571 2518 731 572 2519 732 574 2520 734 571 2521 731 573 2522 733 571 2523 731 574 2524 734 572 2525 732 576 2526 694 573 2527 733 575 2528 695 573 2529 733 576 2530 694 574 2531 734 559 2532 717 557 2533 715 497 2534 735 497 2535 735 557 2536 715 498 2537 736 499 2538 737 557 2539 715 555 2540 713 557 2541 715 499 2542 737 498 2543 736 500 2544 738 555 2545 713 553 2546 711 555 2547 713 500 2548 738 499 2549 737 501 2550 739 553 2551 711 551 2552 709 553 2553 711 501 2554 739 500 2555 738 502 2556 740 501 2557 739 549 2558 707 549 2559 707 501 2560 739 551 2561 709 503 2562 741 502 2563 740 547 2564 705 547 2565 705 502 2566 740 549 2567 707 547 2568 705 504 2569 742 503 2570 741 504 2571 742 547 2572 705 545 2573 703 545 2574 703 505 2575 743 504 2576 742 505 2577 743 545 2578 703 543 2579 701 543 2580 701 506 2581 744 505 2582 743 506 2583 744 543 2584 701 541 2585 699 541 2586 699 539 2587 697 506 2588 744 506 2589 744 539 2590 697 507 2591 745 507 2592 745 538 2593 696 508 2594 746 538 2595 696 507 2596 745 539 2597 697 538 2598 696 509 2599 747 508 2600 746 509 2601 747 538 2602 696 575 2603 695 575 2604 695 510 2605 748 509 2606 747 510 2607 748 575 2608 695 573 2609 733 573 2610 733 511 2611 749 510 2612 748 511 2613 749 573 2614 733 571 2615 731 571 2616 731 569 2617 729 511 2618 749 511 2619 749 569 2620 729 512 2621 750 569 2622 729 567 2623 727 512 2624 750 512 2625 750 567 2626 727 513 2627 751 567 2628 727 514 2629 752 513 2630 751 514 2631 752 567 2632 727 565 2633 725 565 2634 725 515 2635 753 514 2636 752 515 2637 753 565 2638 725 563 2639 722 563 2640 722 516 2641 754 515 2642 753 516 2643 754 563 2644 722 561 2645 721 561 2646 719 559 2647 717 516 2648 755 516 2649 755 559 2650 717 497 2651 735 537 2652 693 540 2653 698 527 2654 756 527 2655 756 528 2656 757 537 2657 693 526 2658 758 540 2659 698 542 2660 700 540 2661 698 526 2662 758 527 2663 756 525 2664 759 526 2665 758 544 2666 702 544 2667 702 526 2668 758 542 2669 700 524 2670 760 525 2671 759 546 2672 704 546 2673 704 525 2674 759 544 2675 702 523 2676 761 524 2677 760 548 2678 706 548 2679 706 524 2680 760 546 2681 704 548 2682 706 522 2683 762 523 2684 761 522 2685 762 548 2686 706 550 2687 708 550 2688 708 521 2689 763 522 2690 762 521 2691 763 550 2692 708 552 2693 710 552 2694 710 554 2695 712 521 2696 763 521 2697 763 554 2698 712 520 2699 764 554 2700 712 556 2701 714 520 2702 764 520 2703 764 556 2704 714 519 2705 765 519 2706 765 556 2707 714 558 2708 716 519 2709 765 558 2710 716 518 2711 766 517 2712 767 558 2713 716 560 2714 718 558 2715 716 517 2716 767 518 2717 766 536 2718 768 560 2719 718 562 2720 720 560 2721 718 536 2722 768 517 2723 767 535 2724 769 536 2725 770 564 2726 723 564 2727 723 536 2728 770 562 2729 724 534 2730 771 535 2731 769 566 2732 726 566 2733 726 535 2734 769 564 2735 723 533 2736 772 534 2737 771 568 2738 728 568 2739 728 534 2740 771 566 2741 726 532 2742 773 568 2743 728 570 2744 730 568 2745 728 532 2746 773 533 2747 772 531 2748 774 570 2749 730 572 2750 732 570 2751 730 531 2752 774 532 2753 773 530 2754 775 531 2755 774 574 2756 734 574 2757 734 531 2758 774 572 2759 732 529 2760 776 530 2761 775 576 2762 694 576 2763 694 530 2764 775 574 2765 734 528 2766 757 529 2767 776 537 2768 693 537 2769 693 529 2770 776 576 2771 694 617 2772 778 578 2773 780 616 2774 777 578 2775 780 617 2776 778 579 2777 779 579 2778 779 580 2779 782 578 2780 780 580 2781 782 579 2782 779 581 2783 781 581 2784 781 582 2785 784 580 2786 782 582 2787 784 581 2788 781 583 2789 783 583 2790 783 584 2791 786 582 2792 784 584 2793 786 583 2794 783 585 2795 785 585 2796 785 586 2797 788 584 2798 786 586 2799 788 585 2800 785 587 2801 787 588 2802 790 586 2803 788 589 2804 789 589 2805 789 586 2806 788 587 2807 787 589 2808 789 590 2809 792 588 2810 790 590 2811 792 589 2812 789 591 2813 791 593 2814 793 590 2815 792 591 2816 791 590 2817 792 593 2818 793 592 2819 794 594 2820 796 592 2821 794 593 2822 793 593 2823 793 595 2824 795 594 2825 796 595 2826 795 596 2827 798 594 2828 796 596 2829 798 595 2830 795 597 2831 797 597 2832 797 599 2833 799 596 2834 798 598 2835 800 596 2836 798 599 2837 799 600 2838 802 599 2839 799 601 2840 801 599 2841 799 600 2842 802 598 2843 800 602 2844 804 601 2845 801 603 2846 803 601 2847 801 602 2848 804 600 2849 802 605 2850 805 602 2851 804 603 2852 803 602 2853 804 605 2854 805 604 2855 806 607 2856 807 604 2857 806 605 2858 805 604 2859 806 607 2860 807 606 2861 808 609 2862 809 606 2863 808 607 2864 807 608 2865 810 606 2866 808 609 2867 809 609 2868 809 611 2869 811 608 2870 810 610 2871 812 608 2872 810 611 2873 811 611 2874 811 613 2875 813 610 2876 812 612 2877 814 610 2878 812 613 2879 813 614 2880 816 612 2881 814 615 2882 815 615 2883 815 612 2884 814 613 2885 813 616 2886 777 614 2887 816 617 2888 778 617 2889 778 614 2890 816 615 2891 815 580 2892 782 517 2893 817 578 2894 780 517 2895 817 580 2896 782 518 2897 818 580 2898 782 582 2899 784 518 2900 818 519 2901 819 518 2902 818 582 2903 784 582 2904 784 520 2905 820 519 2906 819 520 2907 820 582 2908 784 584 2909 786 521 2910 821 584 2911 786 586 2912 788 584 2913 786 521 2914 821 520 2915 820 522 2916 822 586 2917 788 588 2918 790 586 2919 788 522 2920 822 521 2921 821 523 2922 823 588 2923 790 590 2924 792 588 2925 790 523 2926 823 522 2927 822 590 2928 792 524 2929 824 523 2930 823 524 2931 824 590 2932 792 592 2933 794 592 2934 794 525 2935 825 524 2936 824 525 2937 825 592 2938 794 594 2939 796 594 2940 796 596 2941 798 525 2942 825 526 2943 826 525 2944 825 596 2945 798 527 2946 827 526 2947 826 598 2948 800 526 2949 826 596 2950 798 598 2951 800 528 2952 828 527 2953 827 600 2954 802 600 2955 802 527 2956 827 598 2957 800 528 2958 828 602 2959 804 529 2960 829 602 2961 804 528 2962 828 600 2963 802 604 2964 806 529 2965 829 602 2966 804 529 2967 829 604 2968 806 530 2969 830 606 2970 808 530 2971 830 604 2972 806 530 2973 830 606 2974 808 531 2975 831 608 2976 810 531 2977 831 606 2978 808 531 2979 831 608 2980 810 532 2981 832 608 2982 810 610 2983 812 532 2984 832 533 2985 833 532 2986 832 610 2987 812 534 2988 834 610 2989 812 612 2990 814 610 2991 812 534 2992 834 533 2993 833 535 2994 835 612 2995 814 614 2996 816 612 2997 814 535 2998 835 534 2999 834 535 3000 835 616 3001 777 536 3002 836 616 3003 777 535 3004 835 614 3005 816 616 3006 777 517 3007 817 536 3008 836 517 3009 817 616 3010 777 578 3011 780 579 3012 779 577 3013 837 581 3014 781 581 3015 781 577 3016 837 583 3017 783 583 3018 783 577 3019 837 585 3020 785 585 3021 785 577 3022 837 587 3023 787 587 3024 787 577 3025 837 589 3026 789 589 3027 789 577 3028 837 591 3029 791 591 3030 791 577 3031 837 593 3032 793 593 3033 793 577 3034 837 595 3035 795 595 3036 795 577 3037 837 597 3038 797 597 3039 797 577 3040 837 599 3041 799 599 3042 799 577 3043 837 601 3044 801 601 3045 801 577 3046 837 603 3047 803 603 3048 803 577 3049 837 605 3050 805 605 3051 805 577 3052 837 607 3053 807 607 3054 807 577 3055 837 609 3056 809 609 3057 809 577 3058 837 611 3059 811 611 3060 811 577 3061 837 613 3062 813 613 3063 813 577 3064 837 615 3065 815 615 3066 815 577 3067 837 617 3068 778 617 3069 778 577 3070 837 579 3071 779 619 3072 841 618 3073 838 639 3074 840 639 3075 840 618 3076 838 638 3077 839 620 3078 843 639 3079 840 640 3080 842 639 3081 840 620 3082 843 619 3083 841 621 3084 845 640 3085 842 641 3086 844 640 3087 842 621 3088 845 620 3089 843 622 3090 847 641 3091 844 642 3092 846 641 3093 844 622 3094 847 621 3095 845 623 3096 849 622 3097 847 643 3098 848 643 3099 848 622 3100 847 642 3101 846 624 3102 851 623 3103 849 644 3104 850 644 3105 850 623 3106 849 643 3107 848 645 3108 852 625 3109 853 624 3110 851 645 3111 852 624 3112 851 644 3113 850 626 3114 855 625 3115 853 646 3116 854 646 3117 854 625 3118 853 645 3119 852 627 3120 857 626 3121 855 647 3122 856 647 3123 856 626 3124 855 646 3125 854 628 3126 859 627 3127 857 648 3128 858 648 3129 858 627 3130 857 647 3131 856 629 3132 861 628 3133 859 649 3134 860 649 3135 860 628 3136 859 648 3137 858 650 3138 862 630 3139 863 629 3140 861 650 3141 862 629 3142 861 649 3143 860 651 3144 864 630 3145 863 650 3146 862 630 3147 863 651 3148 864 631 3149 865 651 3150 864 652 3151 866 631 3152 865 631 3153 865 652 3154 866 632 3155 867 652 3156 866 653 3157 868 632 3158 867 632 3159 867 653 3160 868 633 3161 869 653 3162 868 634 3163 871 633 3164 869 634 3165 871 653 3166 868 654 3167 870 655 3168 872 635 3169 873 634 3170 871 655 3171 872 634 3172 871 654 3173 870 636 3174 875 635 3175 873 656 3176 874 656 3177 874 635 3178 873 655 3179 872 637 3180 877 636 3181 875 657 3182 876 657 3183 876 636 3184 875 656 3185 874 618 3186 879 657 3187 876 638 3188 878 657 3189 876 618 3190 879 637 3191 877 658 3192 881 639 3193 883 638 3194 880 639 3195 883 658 3196 881 659 3197 882 659 3198 882 640 3199 885 639 3200 883 640 3201 885 659 3202 882 660 3203 884 660 3204 884 641 3205 887 640 3206 885 641 3207 887 660 3208 884 661 3209 886 642 3210 889 661 3211 886 662 3212 888 661 3213 886 642 3214 889 641 3215 887 643 3216 891 662 3217 888 663 3218 890 662 3219 888 643 3220 891 642 3221 889 643 3222 891 664 3223 892 644 3224 893 664 3225 892 643 3226 891 663 3227 890 664 3228 892 645 3229 895 644 3230 893 645 3231 895 664 3232 892 665 3233 894 666 3234 896 645 3235 895 665 3236 894 645 3237 895 666 3238 896 646 3239 897 666 3240 896 667 3241 898 646 3242 897 647 3243 899 646 3244 897 667 3245 898 648 3246 901 667 3247 898 668 3248 900 667 3249 898 648 3250 901 647 3251 899 649 3252 903 668 3253 900 669 3254 902 668 3255 900 649 3256 903 648 3257 901 649 3258 903 670 3259 904 650 3260 905 670 3261 904 649 3262 903 669 3263 902 671 3264 906 650 3265 905 670 3266 904 650 3267 905 671 3268 906 651 3269 907 672 3270 908 651 3271 907 671 3272 906 651 3273 907 672 3274 908 652 3275 909 673 3276 910 652 3277 909 672 3278 908 652 3279 909 673 3280 910 653 3281 911 673 3282 910 674 3283 912 653 3284 911 654 3285 913 653 3286 911 674 3287 912 655 3288 915 654 3289 913 675 3290 914 654 3291 913 674 3292 912 675 3293 914 656 3294 917 655 3295 915 676 3296 916 676 3297 916 655 3298 915 675 3299 914 656 3300 917 677 3301 918 657 3302 919 677 3303 918 656 3304 917 676 3305 916 677 3306 918 638 3307 880 657 3308 919 638 3309 880 677 3310 918 658 3311 881 699 3312 923 698 3313 920 736 3314 922 698 3315 920 737 3316 921 736 3317 922 698 3318 920 699 3319 923 701 3320 925 699 3321 923 700 3322 924 701 3323 925 701 3324 925 700 3325 924 703 3326 927 700 3327 924 702 3328 926 703 3329 927 703 3330 927 702 3331 926 705 3332 929 702 3333 926 704 3334 928 705 3335 929 705 3336 929 704 3337 928 707 3338 931 704 3339 928 706 3340 930 707 3341 931 707 3342 931 706 3343 930 709 3344 933 706 3345 930 708 3346 932 709 3347 933 709 3348 933 708 3349 932 711 3350 935 708 3351 932 710 3352 934 711 3353 935 711 3354 935 710 3355 934 713 3356 937 710 3357 934 712 3358 936 713 3359 937 713 3360 937 712 3361 936 715 3362 939 712 3363 936 714 3364 938 715 3365 939 715 3366 939 714 3367 938 717 3368 941 714 3369 938 716 3370 940 717 3371 941 717 3372 941 716 3373 940 719 3374 943 716 3375 940 718 3376 942 719 3377 943 719 3378 943 718 3379 942 721 3380 945 718 3381 942 720 3382 944 721 3383 945 721 3384 945 720 3385 944 723 3386 947 720 3387 944 722 3388 946 723 3389 947 723 3390 951 724 3391 949 725 3392 950 724 3393 949 723 3394 951 722 3395 948 725 3396 950 726 3397 952 727 3398 953 726 3399 952 725 3400 950 724 3401 949 727 3402 953 726 3403 952 729 3404 955 726 3405 952 728 3406 954 729 3407 955 730 3408 956 729 3409 955 728 3410 954 729 3411 955 730 3412 956 731 3413 957 732 3414 958 731 3415 957 730 3416 956 731 3417 957 732 3418 958 733 3419 959 735 3420 961 732 3421 958 734 3422 960 732 3423 958 735 3424 961 733 3425 959 737 3426 921 734 3427 960 736 3428 922 734 3429 960 737 3430 921 735 3431 961 659 3432 963 658 3433 962 718 3434 942 718 3435 942 658 3436 962 720 3437 944 660 3438 964 718 3439 942 716 3440 940 718 3441 942 660 3442 964 659 3443 963 661 3444 965 716 3445 940 714 3446 938 716 3447 940 661 3448 965 660 3449 964 662 3450 966 714 3451 938 712 3452 936 714 3453 938 662 3454 966 661 3455 965 663 3456 967 662 3457 966 710 3458 934 710 3459 934 662 3460 966 712 3461 936 664 3462 968 663 3463 967 708 3464 932 708 3465 932 663 3466 967 710 3467 934 665 3468 969 708 3469 932 706 3470 930 708 3471 932 665 3472 969 664 3473 968 666 3474 970 706 3475 930 704 3476 928 706 3477 930 666 3478 970 665 3479 969 667 3480 971 704 3481 928 702 3482 926 704 3483 928 667 3484 971 666 3485 970 668 3486 972 667 3487 971 700 3488 924 700 3489 924 667 3490 971 702 3491 926 699 3492 923 668 3493 972 700 3494 924 668 3495 972 699 3496 923 669 3497 973 699 3498 923 670 3499 974 669 3500 973 670 3501 974 699 3502 923 736 3503 922 736 3504 922 671 3505 975 670 3506 974 671 3507 975 736 3508 922 734 3509 960 734 3510 960 672 3511 976 671 3512 975 672 3513 976 734 3514 960 732 3515 958 732 3516 958 730 3517 956 672 3518 976 672 3519 976 730 3520 956 673 3521 977 730 3522 956 728 3523 954 673 3524 977 673 3525 977 728 3526 954 674 3527 978 728 3528 954 726 3529 952 674 3530 978 674 3531 978 726 3532 952 675 3533 979 676 3534 980 726 3535 952 724 3536 949 726 3537 952 676 3538 980 675 3539 979 677 3540 981 724 3541 949 722 3542 948 724 3543 949 677 3544 981 676 3545 980 658 3546 962 677 3547 982 720 3548 944 720 3549 944 677 3550 982 722 3551 946 698 3552 920 688 3553 983 689 3554 984 688 3555 983 698 3556 920 701 3557 925 701 3558 925 687 3559 985 688 3560 983 687 3561 985 701 3562 925 703 3563 927 703 3564 927 705 3565 929 687 3566 985 687 3567 985 705 3568 929 686 3569 986 705 3570 929 707 3571 931 686 3572 986 686 3573 986 707 3574 931 685 3575 987 685 3576 987 707 3577 931 709 3578 933 685 3579 987 709 3580 933 684 3581 988 709 3582 933 683 3583 989 684 3584 988 683 3585 989 709 3586 933 711 3587 935 711 3588 935 682 3589 990 683 3590 989 682 3591 990 711 3592 935 713 3593 937 713 3594 937 715 3595 939 682 3596 990 682 3597 990 715 3598 939 681 3599 991 715 3600 939 717 3601 941 681 3602 991 681 3603 991 717 3604 941 680 3605 992 680 3606 992 717 3607 941 719 3608 943 680 3609 992 719 3610 943 679 3611 993 719 3612 943 678 3613 994 679 3614 993 678 3615 994 719 3616 943 721 3617 945 721 3618 945 697 3619 995 678 3620 994 697 3621 995 721 3622 945 723 3623 947 723 3624 951 725 3625 950 697 3626 997 697 3627 997 725 3628 950 696 3629 996 725 3630 950 727 3631 953 696 3632 996 696 3633 996 727 3634 953 695 3635 998 694 3636 999 727 3637 953 729 3638 955 727 3639 953 694 3640 999 695 3641 998 693 3642 1000 729 3643 955 731 3644 957 729 3645 955 693 3646 1000 694 3647 999 692 3648 1001 731 3649 957 733 3650 959 731 3651 957 692 3652 1001 693 3653 1000 691 3654 1002 692 3655 1001 735 3656 961 735 3657 961 692 3658 1001 733 3659 959 690 3660 1003 691 3661 1002 737 3662 921 737 3663 921 691 3664 1002 735 3665 961 689 3666 984 690 3667 1003 698 3668 920 698 3669 920 690 3670 1003 737 3671 921 778 3672 1005 739 3673 1007 777 3674 1004 739 3675 1007 778 3676 1005 740 3677 1006 740 3678 1006 741 3679 1009 739 3680 1007 741 3681 1009 740 3682 1006 742 3683 1008 742 3684 1008 744 3685 1010 741 3686 1009 743 3687 1011 741 3688 1009 744 3689 1010 744 3690 1010 745 3691 1013 743 3692 1011 745 3693 1013 744 3694 1010 746 3695 1012 746 3696 1012 747 3697 1015 745 3698 1013 747 3699 1015 746 3700 1012 748 3701 1014 749 3702 1017 747 3703 1015 750 3704 1016 750 3705 1016 747 3706 1015 748 3707 1014 750 3708 1016 751 3709 1019 749 3710 1017 751 3711 1019 750 3712 1016 752 3713 1018 752 3714 1018 753 3715 1021 751 3716 1019 753 3717 1021 752 3718 1018 754 3719 1020 755 3720 1023 753 3721 1021 754 3722 1020 754 3723 1020 756 3724 1022 755 3725 1023 756 3726 1022 757 3727 1025 755 3728 1023 757 3729 1025 756 3730 1022 758 3731 1024 758 3732 1024 760 3733 1026 757 3734 1025 759 3735 1027 757 3736 1025 760 3737 1026 761 3738 1029 760 3739 1026 762 3740 1028 760 3741 1026 761 3742 1029 759 3743 1027 763 3744 1031 762 3745 1028 764 3746 1030 762 3747 1028 763 3748 1031 761 3749 1029 766 3750 1032 763 3751 1031 764 3752 1030 763 3753 1031 766 3754 1032 765 3755 1033 768 3756 1034 765 3757 1033 766 3758 1032 765 3759 1033 768 3760 1034 767 3761 1035 770 3762 1036 767 3763 1035 768 3764 1034 769 3765 1037 767 3766 1035 770 3767 1036 770 3768 1036 771 3769 1039 769 3770 1037 771 3771 1039 770 3772 1036 772 3773 1038 772 3774 1038 774 3775 1040 771 3776 1039 773 3777 1041 771 3778 1039 774 3779 1040 775 3780 1043 773 3781 1041 776 3782 1042 776 3783 1042 773 3784 1041 774 3785 1040 777 3786 1004 775 3787 1043 778 3788 1005 778 3789 1005 775 3790 1043 776 3791 1042 739 3792 1007 679 3793 1045 678 3794 1044 679 3795 1045 739 3796 1007 741 3797 1009 741 3798 1009 743 3799 1011 679 3800 1045 680 3801 1046 679 3802 1045 743 3803 1011 743 3804 1011 681 3805 1047 680 3806 1046 681 3807 1047 743 3808 1011 745 3809 1013 682 3810 1048 745 3811 1013 747 3812 1015 745 3813 1013 682 3814 1048 681 3815 1047 683 3816 1049 747 3817 1015 749 3818 1017 747 3819 1015 683 3820 1049 682 3821 1048 684 3822 1050 749 3823 1017 751 3824 1019 749 3825 1017 684 3826 1050 683 3827 1049 751 3828 1019 685 3829 1051 684 3830 1050 685 3831 1051 751 3832 1019 753 3833 1021 753 3834 1021 686 3835 1052 685 3836 1051 686 3837 1052 753 3838 1021 755 3839 1023 755 3840 1023 757 3841 1025 686 3842 1052 687 3843 1053 686 3844 1052 757 3845 1025 688 3846 1054 687 3847 1053 759 3848 1027 687 3849 1053 757 3850 1025 759 3851 1027 689 3852 1055 688 3853 1054 761 3854 1029 761 3855 1029 688 3856 1054 759 3857 1027 689 3858 1055 763 3859 1031 690 3860 1056 763 3861 1031 689 3862 1055 761 3863 1029 765 3864 1033 690 3865 1056 763 3866 1031 690 3867 1056 765 3868 1033 691 3869 1057 767 3870 1035 691 3871 1057 765 3872 1033 691 3873 1057 767 3874 1035 692 3875 1058 769 3876 1037 692 3877 1058 767 3878 1035 692 3879 1058 769 3880 1037 693 3881 1059 769 3882 1037 771 3883 1039 693 3884 1059 694 3885 1060 693 3886 1059 771 3887 1039 695 3888 1061 771 3889 1039 773 3890 1041 771 3891 1039 695 3892 1061 694 3893 1060 696 3894 1062 773 3895 1041 775 3896 1043 773 3897 1041 696 3898 1062 695 3899 1061 696 3900 1062 777 3901 1004 697 3902 1063 777 3903 1004 696 3904 1062 775 3905 1043 777 3906 1004 678 3907 1044 697 3908 1063 678 3909 1044 777 3910 1004 739 3911 1007 740 3912 1006 738 3913 1064 742 3914 1008 742 3915 1008 738 3916 1064 744 3917 1010 744 3918 1010 738 3919 1064 746 3920 1012 746 3921 1012 738 3922 1064 748 3923 1014 748 3924 1014 738 3925 1064 750 3926 1016 750 3927 1016 738 3928 1064 752 3929 1018 752 3930 1018 738 3931 1064 754 3932 1020 754 3933 1020 738 3934 1064 756 3935 1022 756 3936 1022 738 3937 1064 758 3938 1024 758 3939 1024 738 3940 1064 760 3941 1026 760 3942 1026 738 3943 1064 762 3944 1028 762 3945 1028 738 3946 1064 764 3947 1030 764 3948 1030 738 3949 1064 766 3950 1032 766 3951 1032 738 3952 1064 768 3953 1034 768 3954 1034 738 3955 1064 770 3956 1036 770 3957 1036 738 3958 1064 772 3959 1038 772 3960 1038 738 3961 1064 774 3962 1040 774 3963 1040 738 3964 1064 776 3965 1042 776 3966 1042 738 3967 1064 778 3968 1005 778 3969 1005 738 3970 1064 740 3971 1006 800 3972 1067 799 3973 1068 779 3974 1065 779 3975 1065 780 3976 1066 800 3977 1067 781 3978 1069 800 3979 1067 780 3980 1066 800 3981 1067 781 3982 1069 801 3983 1070 782 3984 1071 801 3985 1070 781 3986 1069 801 3987 1070 782 3988 1071 802 3989 1072 783 3990 1073 802 3991 1072 782 3992 1071 802 3993 1072 783 3994 1073 803 3995 1074 804 3996 1076 783 3997 1073 784 3998 1075 783 3999 1073 804 4000 1076 803 4001 1074 805 4002 1078 784 4003 1075 785 4004 1077 784 4005 1075 805 4006 1078 804 4007 1076 805 4008 1078 785 4009 1077 806 4010 1080 785 4011 1077 786 4012 1079 806 4013 1080 807 4014 1082 806 4015 1080 786 4016 1079 786 4017 1079 787 4018 1081 807 4019 1082 808 4020 1084 807 4021 1082 787 4022 1081 787 4023 1081 788 4024 1083 808 4025 1084 809 4026 1086 808 4027 1084 788 4028 1083 788 4029 1083 789 4030 1085 809 4031 1086 810 4032 1088 809 4033 1086 789 4034 1085 789 4035 1085 790 4036 1087 810 4037 1088 810 4038 1088 790 4039 1087 811 4040 1090 790 4041 1087 791 4042 1089 811 4043 1090 812 4044 1092 811 4045 1090 791 4046 1089 791 4047 1089 792 4048 1091 812 4049 1092 813 4050 1094 812 4051 1092 792 4052 1091 792 4053 1091 793 4054 1093 813 4055 1094 814 4056 1096 813 4057 1094 793 4058 1093 793 4059 1093 794 4060 1095 814 4061 1096 814 4062 1096 795 4063 1097 815 4064 1098 795 4065 1097 814 4066 1096 794 4067 1095 815 4068 1098 796 4069 1099 816 4070 1100 796 4071 1099 815 4072 1098 795 4073 1097 817 4074 1102 816 4075 1100 796 4076 1099 796 4077 1099 797 4078 1101 817 4079 1102 818 4080 1104 817 4081 1102 797 4082 1101 797 4083 1101 798 4084 1103 818 4085 1104 818 4086 1104 779 4087 1105 799 4088 1106 779 4089 1105 818 4090 1104 798 4091 1103 819 4092 1110 800 4093 1108 820 4094 1109 800 4095 1108 819 4096 1110 799 4097 1107 801 4098 1111 820 4099 1109 800 4100 1108 820 4101 1109 801 4102 1111 821 4103 1112 802 4104 1113 821 4105 1112 801 4106 1111 821 4107 1112 802 4108 1113 822 4109 1114 803 4110 1115 822 4111 1114 802 4112 1113 822 4113 1114 803 4114 1115 823 4115 1116 823 4116 1116 804 4117 1117 824 4118 1118 804 4119 1117 823 4120 1116 803 4121 1115 804 4122 1117 825 4123 1120 824 4124 1118 825 4125 1120 804 4126 1117 805 4127 1119 825 4128 1120 806 4129 1121 826 4130 1122 806 4131 1121 825 4132 1120 805 4133 1119 827 4134 1124 826 4135 1122 806 4136 1121 806 4137 1121 807 4138 1123 827 4139 1124 807 4140 1123 808 4141 1125 828 4142 1126 807 4143 1123 828 4144 1126 827 4145 1124 809 4146 1127 828 4147 1126 808 4148 1125 828 4149 1126 809 4150 1127 829 4151 1128 810 4152 1129 829 4153 1128 809 4154 1127 829 4155 1128 810 4156 1129 830 4157 1130 810 4158 1129 831 4159 1132 830 4160 1130 831 4161 1132 810 4162 1129 811 4163 1131 832 4164 1134 831 4165 1132 811 4166 1131 811 4167 1131 812 4168 1133 832 4169 1134 833 4170 1136 832 4171 1134 812 4172 1133 812 4173 1133 813 4174 1135 833 4175 1136 813 4176 1135 814 4177 1137 834 4178 1138 813 4179 1135 834 4180 1138 833 4181 1136 814 4182 1137 815 4183 1139 835 4184 1140 814 4185 1137 835 4186 1140 834 4187 1138 836 4188 1142 815 4189 1139 816 4190 1141 815 4191 1139 836 4192 1142 835 4193 1140 817 4194 1143 836 4195 1142 816 4196 1141 836 4197 1142 817 4198 1143 837 4199 1144 817 4200 1143 838 4201 1146 837 4202 1144 838 4203 1146 817 4204 1143 818 4205 1145 838 4206 1146 799 4207 1107 819 4208 1110 799 4209 1107 838 4210 1146 818 4211 1145 860 4212 1148 897 4213 1149 859 4214 1147 859 4215 1147 897 4216 1149 898 4217 1150 862 4218 1151 861 4219 1152 860 4220 1148 862 4221 1151 860 4222 1148 859 4223 1147 864 4224 1153 863 4225 1154 861 4226 1152 864 4227 1153 861 4228 1152 862 4229 1151 866 4230 1155 865 4231 1156 863 4232 1154 866 4233 1155 863 4234 1154 864 4235 1153 868 4236 1157 867 4237 1158 865 4238 1156 868 4239 1157 865 4240 1156 866 4241 1155 869 4242 1160 868 4243 1157 870 4244 1159 868 4245 1157 869 4246 1160 867 4247 1158 870 4248 1159 872 4249 1161 869 4250 1160 869 4251 1160 872 4252 1161 871 4253 1162 874 4254 1163 871 4255 1162 872 4256 1161 871 4257 1162 874 4258 1163 873 4259 1164 874 4260 1163 876 4261 1165 873 4262 1164 873 4263 1164 876 4264 1165 875 4265 1166 876 4266 1165 878 4267 1167 875 4268 1166 875 4269 1166 878 4270 1167 877 4271 1168 880 4272 1169 877 4273 1168 878 4274 1167 877 4275 1168 880 4276 1169 879 4277 1170 882 4278 1171 881 4279 1172 879 4280 1170 882 4281 1171 879 4282 1170 880 4283 1169 884 4284 1173 883 4285 1174 881 4286 1172 884 4287 1173 881 4288 1172 882 4289 1171 885 4290 1178 884 4291 1176 886 4292 1177 884 4293 1176 885 4294 1178 883 4295 1175 887 4296 1180 886 4297 1177 888 4298 1179 886 4299 1177 887 4300 1180 885 4301 1178 890 4302 1181 889 4303 1182 887 4304 1180 890 4305 1181 887 4306 1180 888 4307 1179 891 4308 1184 890 4309 1181 892 4310 1183 890 4311 1181 891 4312 1184 889 4313 1182 893 4314 1186 892 4315 1183 894 4316 1185 892 4317 1183 893 4318 1186 891 4319 1184 896 4320 1187 895 4321 1188 893 4322 1186 896 4323 1187 893 4324 1186 894 4325 1185 898 4326 1150 897 4327 1149 895 4328 1188 898 4329 1150 895 4330 1188 896 4331 1187 879 4332 1170 881 4333 1172 819 4334 1189 819 4335 1189 820 4336 1190 879 4337 1170 821 4338 1191 879 4339 1170 820 4340 1190 879 4341 1170 821 4342 1191 877 4343 1168 822 4344 1192 877 4345 1168 821 4346 1191 877 4347 1168 822 4348 1192 875 4349 1166 823 4350 1193 875 4351 1166 822 4352 1192 875 4353 1166 823 4354 1193 873 4355 1164 871 4356 1162 823 4357 1193 824 4358 1194 823 4359 1193 871 4360 1162 873 4361 1164 869 4362 1160 824 4363 1194 825 4364 1195 824 4365 1194 869 4366 1160 871 4367 1162 869 4368 1160 826 4369 1196 867 4370 1158 826 4371 1196 869 4372 1160 825 4373 1195 867 4374 1158 827 4375 1197 865 4376 1156 827 4377 1197 867 4378 1158 826 4379 1196 865 4380 1156 828 4381 1198 863 4382 1154 828 4383 1198 865 4384 1156 827 4385 1197 861 4386 1152 863 4387 1154 828 4388 1198 828 4389 1198 829 4390 1199 861 4391 1152 829 4392 1199 860 4393 1148 861 4394 1152 860 4395 1148 829 4396 1199 830 4397 1200 860 4398 1148 831 4399 1201 897 4400 1149 831 4401 1201 860 4402 1148 830 4403 1200 897 4404 1149 832 4405 1202 895 4406 1188 832 4407 1202 897 4408 1149 831 4409 1201 895 4410 1188 833 4411 1203 893 4412 1186 833 4413 1203 895 4414 1188 832 4415 1202 891 4416 1184 893 4417 1186 833 4418 1203 833 4419 1203 834 4420 1204 891 4421 1184 889 4422 1182 891 4423 1184 834 4424 1204 834 4425 1204 835 4426 1205 889 4427 1182 889 4428 1182 836 4429 1206 887 4430 1180 836 4431 1206 889 4432 1182 835 4433 1205 887 4434 1180 837 4435 1207 885 4436 1178 837 4437 1207 887 4438 1180 836 4439 1206 885 4440 1178 838 4441 1208 883 4442 1175 838 4443 1208 885 4444 1178 837 4445 1207 881 4446 1172 883 4447 1174 838 4448 1209 838 4449 1209 819 4450 1189 881 4451 1172 862 4452 1151 859 4453 1147 849 4454 1210 849 4455 1210 859 4456 1147 850 4457 1211 848 4458 1212 862 4459 1151 849 4460 1210 862 4461 1151 848 4462 1212 864 4463 1153 848 4464 1212 847 4465 1213 866 4466 1155 866 4467 1155 864 4468 1153 848 4469 1212 847 4470 1213 846 4471 1214 868 4472 1157 868 4473 1157 866 4474 1155 847 4475 1213 845 4476 1215 870 4477 1159 846 4478 1214 870 4479 1159 868 4480 1157 846 4481 1214 870 4482 1159 844 4483 1216 872 4484 1161 844 4485 1216 870 4486 1159 845 4487 1215 872 4488 1161 843 4489 1217 874 4490 1163 843 4491 1217 872 4492 1161 844 4493 1216 843 4494 1217 876 4495 1165 874 4496 1163 876 4497 1165 843 4498 1217 842 4499 1218 842 4500 1218 878 4501 1167 876 4502 1165 878 4503 1167 842 4504 1218 841 4505 1219 841 4506 1219 880 4507 1169 878 4508 1167 880 4509 1169 841 4510 1219 840 4511 1220 839 4512 1221 880 4513 1169 840 4514 1220 880 4515 1169 839 4516 1221 882 4517 1171 858 4518 1222 882 4519 1171 839 4520 1221 882 4521 1171 858 4522 1222 884 4523 1173 858 4524 1223 857 4525 1224 886 4526 1177 886 4527 1177 884 4528 1176 858 4529 1223 857 4530 1224 856 4531 1225 888 4532 1179 888 4533 1179 886 4534 1177 857 4535 1224 855 4536 1226 890 4537 1181 856 4538 1225 890 4539 1181 888 4540 1179 856 4541 1225 854 4542 1227 890 4543 1181 855 4544 1226 890 4545 1181 854 4546 1227 892 4547 1183 853 4548 1228 892 4549 1183 854 4550 1227 892 4551 1183 853 4552 1228 894 4553 1185 853 4554 1228 852 4555 1229 896 4556 1187 896 4557 1187 894 4558 1185 853 4559 1228 852 4560 1229 851 4561 1230 898 4562 1150 898 4563 1150 896 4564 1187 852 4565 1229 850 4566 1211 898 4567 1150 851 4568 1230 898 4569 1150 850 4570 1211 859 4571 1147 939 4572 1234 900 4573 1232 901 4574 1233 900 4575 1232 939 4576 1234 938 4577 1231 901 4578 1233 902 4579 1235 903 4580 1236 902 4581 1235 901 4582 1233 900 4583 1232 903 4584 1236 904 4585 1237 905 4586 1238 904 4587 1237 903 4588 1236 902 4589 1235 906 4590 1239 905 4591 1238 904 4592 1237 905 4593 1238 906 4594 1239 907 4595 1240 908 4596 1241 907 4597 1240 906 4598 1239 907 4599 1240 908 4600 1241 909 4601 1242 908 4602 1241 911 4603 1244 909 4604 1242 911 4605 1244 908 4606 1241 910 4607 1243 911 4608 1244 912 4609 1245 913 4610 1246 912 4611 1245 911 4612 1244 910 4613 1243 915 4614 1248 913 4615 1246 912 4616 1245 912 4617 1245 914 4618 1247 915 4619 1248 914 4620 1247 916 4621 1249 915 4622 1248 915 4623 1248 916 4624 1249 917 4625 1250 917 4626 1250 918 4627 1251 919 4628 1252 918 4629 1251 917 4630 1250 916 4631 1249 921 4632 1254 918 4633 1251 920 4634 1253 918 4635 1251 921 4636 1254 919 4637 1252 922 4638 1255 921 4639 1254 920 4640 1253 921 4641 1254 922 4642 1255 923 4643 1256 923 4644 1256 924 4645 1257 925 4646 1258 924 4647 1257 923 4648 1256 922 4649 1255 927 4650 1260 925 4651 1258 924 4652 1257 927 4653 1260 924 4654 1257 926 4655 1259 929 4656 1262 927 4657 1260 926 4658 1259 926 4659 1259 928 4660 1261 929 4661 1262 931 4662 1264 929 4663 1262 928 4664 1261 928 4665 1261 930 4666 1263 931 4667 1264 930 4668 1263 932 4669 1265 933 4670 1266 930 4671 1263 933 4672 1266 931 4673 1264 935 4674 1268 932 4675 1265 934 4676 1267 932 4677 1265 935 4678 1268 933 4679 1266 934 4680 1267 937 4681 1270 935 4682 1268 937 4683 1270 934 4684 1267 936 4685 1269 936 4686 1269 939 4687 1234 937 4688 1270 939 4689 1234 936 4690 1269 938 4691 1231 902 4692 1235 900 4693 1232 839 4694 1271 839 4695 1271 840 4696 1272 902 4697 1235 840 4698 1272 841 4699 1273 904 4700 1237 840 4701 1272 904 4702 1237 902 4703 1235 842 4704 1274 904 4705 1237 841 4706 1273 904 4707 1237 842 4708 1274 906 4709 1239 843 4710 1275 906 4711 1239 842 4712 1274 906 4713 1239 843 4714 1275 908 4715 1241 908 4716 1241 844 4717 1276 910 4718 1243 844 4719 1276 908 4720 1241 843 4721 1275 910 4722 1243 845 4723 1277 912 4724 1245 845 4725 1277 910 4726 1243 844 4727 1276 912 4728 1245 846 4729 1278 914 4730 1247 846 4731 1278 912 4732 1245 845 4733 1277 914 4734 1247 847 4735 1279 916 4736 1249 847 4737 1279 914 4738 1247 846 4739 1278 847 4740 1279 848 4741 1280 918 4742 1251 847 4743 1279 918 4744 1251 916 4745 1249 920 4746 1253 848 4747 1280 849 4748 1281 848 4749 1280 920 4750 1253 918 4751 1251 922 4752 1255 849 4753 1281 850 4754 1282 849 4755 1281 922 4756 1255 920 4757 1253 850 4758 1282 924 4759 1257 922 4760 1255 924 4761 1257 850 4762 1282 851 4763 1283 926 4764 1259 924 4765 1257 851 4766 1283 851 4767 1283 852 4768 1284 926 4769 1259 928 4770 1261 926 4771 1259 852 4772 1284 852 4773 1284 853 4774 1285 928 4775 1261 853 4776 1285 854 4777 1286 930 4778 1263 853 4779 1285 930 4780 1263 928 4781 1261 854 4782 1286 855 4783 1287 932 4784 1265 854 4785 1286 932 4786 1265 930 4787 1263 856 4788 1288 932 4789 1265 855 4790 1287 932 4791 1265 856 4792 1288 934 4793 1267 857 4794 1289 934 4795 1267 856 4796 1288 934 4797 1267 857 4798 1289 936 4799 1269 857 4800 1289 938 4801 1231 936 4802 1269 938 4803 1231 857 4804 1289 858 4805 1290 938 4806 1231 839 4807 1271 900 4808 1232 839 4809 1271 938 4810 1231 858 4811 1290 901 4812 1233 903 4813 1236 899 4814 1291 903 4815 1236 905 4816 1238 899 4817 1291 905 4818 1238 907 4819 1240 899 4820 1291 907 4821 1240 909 4822 1242 899 4823 1291 909 4824 1242 911 4825 1244 899 4826 1291 911 4827 1244 913 4828 1246 899 4829 1291 913 4830 1246 915 4831 1248 899 4832 1291 915 4833 1248 917 4834 1250 899 4835 1291 917 4836 1250 919 4837 1252 899 4838 1291 919 4839 1252 921 4840 1254 899 4841 1291 921 4842 1254 923 4843 1256 899 4844 1291 923 4845 1256 925 4846 1258 899 4847 1291 925 4848 1258 927 4849 1260 899 4850 1291 927 4851 1260 929 4852 1262 899 4853 1291 929 4854 1262 931 4855 1264 899 4856 1291 931 4857 1264 933 4858 1266 899 4859 1291 933 4860 1266 935 4861 1268 899 4862 1291 935 4863 1268 937 4864 1270 899 4865 1291 937 4866 1270 939 4867 1234 899 4868 1291 939 4869 1234 901 4870 1233 899 4871 1291 951 4872 1294 940 4873 1292 941 4874 1293 940 4875 1292 951 4876 1294 950 4877 1295 952 4878 1297 941 4879 1293 942 4880 1296 941 4881 1293 952 4882 1297 951 4883 1294 953 4884 1299 942 4885 1296 943 4886 1298 942 4887 1296 953 4888 1299 952 4889 1297 954 4890 1301 943 4891 1298 944 4892 1300 943 4893 1298 954 4894 1301 953 4895 1299 955 4896 1304 944 4897 1302 945 4898 1303 944 4899 1302 955 4900 1304 954 4901 1305 956 4902 1307 945 4903 1303 946 4904 1306 945 4905 1303 956 4906 1307 955 4907 1304 957 4908 1309 946 4909 1306 947 4910 1308 946 4911 1306 957 4912 1309 956 4913 1307 958 4914 1311 947 4915 1308 948 4916 1310 947 4917 1308 958 4918 1311 957 4919 1309 958 4920 1311 948 4921 1310 959 4922 1313 948 4923 1310 949 4924 1312 959 4925 1313 959 4926 1313 949 4927 1312 950 4928 1295 949 4929 1312 940 4930 1292 950 4931 1295 1005 4932 1314 1002 4933 1315 1003 4934 1316 1005 4935 1314 1003 4936 1316 1004 4937 1317 964 4938 1319 965 4939 1320 963 4940 1318 966 4941 1321 963 4942 1318 965 4943 1320 967 4944 1322 965 4945 1320 964 4946 1319 965 4947 1320 967 4948 1322 968 4949 1323 960 4950 1324 961 4951 1325 969 4952 1326 971 4953 1328 967 4954 1322 970 4955 1327 967 4956 1322 971 4957 1328 968 4958 1323 973 4959 1330 975 4960 1332 972 4961 1329 975 4962 1332 973 4963 1330 974 4964 1331 977 4965 1333 971 4966 1328 970 4967 1327 971 4968 1328 977 4969 1333 978 4970 1334 972 4971 1329 975 4972 1332 979 4973 1335 980 4974 1336 979 4975 1335 975 4976 1332 961 4977 1325 981 4978 1337 969 4979 1326 981 4980 1337 982 4981 1338 969 4982 1326 984 4983 1340 979 4984 1335 980 4985 1336 979 4986 1335 984 4987 1340 983 4988 1339 983 4989 1339 984 4990 1340 985 4991 1341 986 4992 1342 985 4993 1341 984 4994 1340 976 4995 1343 962 4996 1344 987 4997 1345 988 4998 1349 982 4999 1346 989 5000 1348 989 5001 1348 982 5002 1346 981 5003 1347 989 5004 1351 987 5005 1345 988 5006 1350 987 5007 1345 989 5008 1351 976 5009 1343 973 5010 1330 963 5011 1318 974 5012 1331 974 5013 1331 963 5014 1318 966 5015 1321 977 5016 1333 985 5017 1341 978 5018 1334 978 5019 1334 985 5020 1341 986 5021 1342 960 5022 1353 969 5023 1354 964 5024 1352 964 5025 1352 969 5026 1354 967 5027 1355 985 5028 1356 988 5029 1357 983 5030 1358 974 5031 1362 940 5032 1360 975 5033 1361 940 5034 1360 974 5035 1362 941 5036 1359 980 5037 1364 940 5038 1360 949 5039 1363 980 5040 1364 975 5041 1361 940 5042 1360 948 5043 1365 980 5044 1364 949 5045 1363 980 5046 1364 948 5047 1365 984 5048 1366 986 5049 1368 984 5050 1366 948 5051 1365 948 5052 1365 947 5053 1367 986 5054 1368 978 5055 1370 986 5056 1368 947 5057 1367 947 5058 1367 946 5059 1369 978 5060 1370 945 5061 1371 978 5062 1370 946 5063 1369 978 5064 1370 945 5065 1371 971 5066 1372 968 5067 1374 971 5068 1372 945 5069 1371 945 5070 1371 944 5071 1373 968 5072 1374 968 5073 1374 943 5074 1375 965 5075 1376 943 5076 1375 968 5077 1374 944 5078 1373 966 5079 1378 965 5080 1376 943 5081 1375 966 5082 1378 943 5083 1375 942 5084 1377 974 5085 1362 966 5086 1378 942 5087 1377 942 5088 1377 941 5089 1359 974 5090 1362 969 5091 1354 970 5092 1380 967 5093 1355 970 5094 1380 969 5095 1354 982 5096 1379 982 5097 1379 977 5098 1381 970 5099 1380 982 5100 1379 988 5101 1357 985 5102 1356 982 5103 1379 985 5104 1356 977 5105 1381 988 5106 1357 987 5107 1382 983 5108 1358 983 5109 1358 987 5110 1382 979 5111 1383 962 5112 1384 973 5113 1385 972 5114 1386 963 5115 1387 960 5116 1353 964 5117 1352 972 5118 1386 987 5119 1382 962 5120 1384 987 5121 1382 972 5122 1386 979 5123 1383 962 5124 1384 960 5125 1353 963 5126 1387 962 5127 1384 963 5128 1387 973 5129 1385 951 5130 1389 990 5131 1391 950 5132 1388 990 5133 1391 951 5134 1389 991 5135 1390 951 5136 1389 952 5137 1392 992 5138 1393 951 5139 1389 992 5140 1393 991 5141 1390 992 5142 1393 952 5143 1392 993 5144 1395 952 5145 1392 953 5146 1394 993 5147 1395 954 5148 1396 993 5149 1395 953 5150 1394 993 5151 1395 954 5152 1396 994 5153 1397 954 5154 1396 995 5155 1399 994 5156 1397 995 5157 1399 954 5158 1396 955 5159 1398 995 5160 1399 956 5161 1400 996 5162 1401 956 5163 1400 995 5164 1399 955 5165 1398 957 5166 1402 997 5167 1403 956 5168 1400 956 5169 1400 997 5170 1403 996 5171 1401 957 5172 1402 998 5173 1405 997 5174 1403 998 5175 1405 957 5176 1402 958 5177 1404 998 5178 1405 959 5179 1406 999 5180 1407 959 5181 1406 998 5182 1405 958 5183 1404 950 5184 1388 990 5185 1391 959 5186 1406 959 5187 1406 990 5188 1391 999 5189 1407 990 5190 1408 991 5191 1409 1000 5192 1410 1001 5193 1412 1000 5194 1410 991 5195 1409 1001 5196 1412 991 5197 1409 992 5198 1411 992 5199 1411 993 5200 1413 1001 5201 1412 1002 5202 1315 993 5203 1413 994 5204 1414 993 5205 1413 1002 5206 1315 1001 5207 1412 1002 5208 1315 995 5209 1415 1003 5210 1316 995 5211 1415 1002 5212 1315 994 5213 1414 995 5214 1415 996 5215 1416 1003 5216 1316 1004 5217 1317 996 5218 1416 997 5219 1417 996 5220 1416 1004 5221 1317 1003 5222 1316 997 5223 1417 998 5224 1418 1004 5225 1317 1005 5226 1314 1004 5227 1317 998 5228 1418 998 5229 1418 999 5230 1419 1005 5231 1314 990 5232 1408 1005 5233 1314 999 5234 1419 1005 5235 1314 990 5236 1408 1000 5237 1410 1002 5238 1315 1005 5239 1314 1000 5240 1410 1002 5241 1315 1000 5242 1410 1001 5243 1412 1006 5244 1420 1016 5245 1421 1017 5246 1422 1006 5247 1420 1017 5248 1422 1007 5249 1423 1017 5250 1422 1018 5251 1424 1007 5252 1423 1007 5253 1423 1018 5254 1424 1008 5255 1425 1008 5256 1425 1018 5257 1424 1019 5258 1426 1008 5259 1425 1019 5260 1426 1009 5261 1427 1019 5262 1426 1020 5263 1428 1009 5264 1427 1009 5265 1427 1020 5266 1428 1010 5267 1429 1020 5268 1428 1021 5269 1430 1010 5270 1429 1010 5271 1429 1021 5272 1430 1011 5273 1431 1011 5274 1432 1021 5275 1433 1022 5276 1434 1011 5277 1432 1022 5278 1434 1012 5279 1435 1022 5280 1434 1023 5281 1436 1012 5282 1435 1012 5283 1435 1023 5284 1436 1013 5285 1437 1013 5286 1437 1023 5287 1436 1024 5288 1438 1013 5289 1437 1024 5290 1438 1014 5291 1439 1025 5292 1440 1015 5293 1441 1014 5294 1439 1025 5295 1440 1014 5296 1439 1024 5297 1438 1016 5298 1421 1006 5299 1420 1015 5300 1441 1016 5301 1421 1015 5302 1441 1025 5303 1440 1065 5304 1444 1067 5305 1442 1066 5306 1443 1064 5307 1445 1067 5308 1442 1065 5309 1444 1028 5310 1448 1027 5311 1449 1026 5312 1446 1028 5313 1448 1026 5314 1446 1029 5315 1447 1028 5316 1448 1030 5317 1451 1027 5318 1449 1030 5319 1451 1028 5320 1448 1031 5321 1450 960 5322 1324 1032 5323 1452 961 5324 1325 1034 5325 1453 1030 5326 1451 1031 5327 1450 1030 5328 1451 1034 5329 1453 1033 5330 1454 1036 5331 1458 1038 5332 1456 1037 5333 1457 1038 5334 1456 1036 5335 1458 1035 5336 1455 1039 5337 1460 1034 5338 1453 1040 5339 1459 1034 5340 1453 1039 5341 1460 1033 5342 1454 1038 5343 1456 1035 5344 1455 1041 5345 1461 1038 5346 1456 1041 5347 1461 1042 5348 1462 1043 5349 1464 961 5350 1325 1032 5351 1452 1032 5352 1452 1044 5353 1463 1043 5354 1464 1041 5355 1461 1046 5356 1466 1042 5357 1462 1046 5358 1466 1041 5359 1461 1045 5360 1465 1046 5361 1466 1045 5362 1465 1047 5363 1467 1046 5364 1466 1047 5365 1467 1048 5366 1468 976 5367 1343 1049 5368 1469 962 5369 1344 1051 5370 1472 1043 5371 1473 1044 5372 1470 1044 5373 1470 1050 5374 1471 1051 5375 1472 1051 5376 1474 1049 5377 1469 976 5378 1343 1049 5379 1469 1051 5380 1474 1050 5381 1475 1026 5382 1478 1037 5383 1476 1029 5384 1477 1037 5385 1476 1026 5386 1478 1036 5387 1479 1047 5388 1482 1040 5389 1480 1048 5390 1481 1040 5391 1480 1047 5392 1482 1039 5393 1483 960 5394 1353 1027 5395 1484 1032 5396 1486 1027 5397 1484 1030 5398 1485 1032 5399 1486 1047 5400 1487 1045 5401 1488 1050 5402 1489 1006 5403 1493 1037 5404 1491 1038 5405 1492 1037 5406 1491 1006 5407 1493 1007 5408 1490 1038 5409 1492 1042 5410 1494 1006 5411 1493 1006 5412 1493 1042 5413 1494 1015 5414 1495 1042 5415 1494 1014 5416 1497 1015 5417 1495 1014 5418 1497 1042 5419 1494 1046 5420 1496 1048 5421 1498 1014 5422 1497 1046 5423 1496 1013 5424 1499 1014 5425 1497 1048 5426 1498 1012 5427 1501 1013 5428 1499 1040 5429 1500 1040 5430 1500 1013 5431 1499 1048 5432 1498 1040 5433 1500 1011 5434 1503 1012 5435 1501 1011 5436 1503 1040 5437 1500 1034 5438 1502 1031 5439 1504 1011 5440 1503 1034 5441 1502 1031 5442 1504 1010 5443 1505 1011 5444 1503 1009 5445 1507 1031 5446 1504 1028 5447 1506 1031 5448 1504 1009 5449 1507 1010 5450 1505 1028 5451 1506 1029 5452 1508 1009 5453 1507 1009 5454 1507 1029 5455 1508 1008 5456 1509 1007 5457 1490 1008 5458 1509 1037 5459 1491 1037 5460 1491 1008 5461 1509 1029 5462 1508 1032 5463 1486 1033 5464 1511 1044 5465 1510 1033 5466 1511 1032 5467 1486 1030 5468 1485 1044 5469 1510 1033 5470 1511 1039 5471 1512 1050 5472 1489 1044 5473 1510 1047 5474 1487 1047 5475 1487 1044 5476 1510 1039 5477 1512 1049 5478 1514 1050 5479 1489 1045 5480 1488 1049 5481 1514 1045 5482 1488 1041 5483 1513 962 5484 1384 1035 5485 1515 1036 5486 1516 1026 5487 1517 1027 5488 1484 960 5489 1353 1049 5490 1514 1035 5491 1515 962 5492 1384 1035 5493 1515 1049 5494 1514 1041 5495 1513 1026 5496 1517 962 5497 1384 1036 5498 1516 960 5499 1353 962 5500 1384 1026 5501 1517 1052 5502 1519 1017 5503 1521 1016 5504 1518 1017 5505 1521 1052 5506 1519 1053 5507 1520 1018 5508 1523 1017 5509 1521 1054 5510 1522 1017 5511 1521 1053 5512 1520 1054 5513 1522 1018 5514 1523 1055 5515 1524 1019 5516 1525 1055 5517 1524 1018 5518 1523 1054 5519 1522 1055 5520 1524 1020 5521 1527 1019 5522 1525 1020 5523 1527 1055 5524 1524 1056 5525 1526 1057 5526 1528 1020 5527 1527 1056 5528 1526 1021 5529 1529 1020 5530 1527 1057 5531 1528 1022 5532 1531 1057 5533 1528 1058 5534 1530 1057 5535 1528 1022 5536 1531 1021 5537 1529 1022 5538 1531 1059 5539 1532 1023 5540 1533 1059 5541 1532 1022 5542 1531 1058 5543 1530 1060 5544 1534 1023 5545 1533 1059 5546 1532 1024 5547 1535 1023 5548 1533 1060 5549 1534 1025 5550 1537 1060 5551 1534 1061 5552 1536 1060 5553 1534 1025 5554 1537 1024 5555 1535 1025 5556 1537 1052 5557 1519 1016 5558 1518 1052 5559 1519 1025 5560 1537 1061 5561 1536 1052 5562 1538 1062 5563 1539 1053 5564 1540 1054 5565 1542 1053 5566 1540 1063 5567 1541 1053 5568 1540 1062 5569 1539 1063 5570 1541 1054 5571 1542 1063 5572 1541 1055 5573 1543 1064 5574 1445 1055 5575 1543 1063 5576 1541 1055 5577 1543 1064 5578 1445 1056 5579 1544 1064 5580 1445 1057 5581 1545 1056 5582 1544 1057 5583 1545 1064 5584 1445 1065 5585 1444 1057 5586 1545 1065 5587 1444 1058 5588 1546 1066 5589 1443 1058 5590 1546 1065 5591 1444 1058 5592 1546 1066 5593 1443 1059 5594 1547 1059 5595 1547 1066 5596 1443 1060 5597 1548 1061 5598 1549 1060 5599 1548 1067 5600 1442 1060 5601 1548 1066 5602 1443 1067 5603 1442 1052 5604 1538 1067 5605 1442 1062 5606 1539 1067 5607 1442 1052 5608 1538 1061 5609 1549 1067 5610 1442 1064 5611 1445 1062 5612 1539 1062 5613 1539 1064 5614 1445 1063 5615 1541 1079 5616 1552 1069 5617 1553 1068 5618 1550 1079 5619 1552 1068 5620 1550 1078 5621 1551 1080 5622 1554 1070 5623 1555 1069 5624 1553 1080 5625 1554 1069 5626 1553 1079 5627 1552 1081 5628 1556 1071 5629 1557 1070 5630 1555 1081 5631 1556 1070 5632 1555 1080 5633 1554 1082 5634 1558 1072 5635 1559 1071 5636 1557 1082 5637 1558 1071 5638 1557 1081 5639 1556 1083 5640 1562 1073 5641 1563 1072 5642 1560 1083 5643 1562 1072 5644 1560 1082 5645 1561 1084 5646 1564 1074 5647 1565 1073 5648 1563 1084 5649 1564 1073 5650 1563 1083 5651 1562 1085 5652 1566 1075 5653 1567 1074 5654 1565 1085 5655 1566 1074 5656 1565 1084 5657 1564 1086 5658 1568 1076 5659 1569 1075 5660 1567 1086 5661 1568 1075 5662 1567 1085 5663 1566 1086 5664 1568 1087 5665 1570 1076 5666 1569 1076 5667 1569 1087 5668 1570 1077 5669 1571 1087 5670 1570 1078 5671 1551 1077 5672 1571 1077 5673 1571 1078 5674 1551 1068 5675 1550 1133 5676 1572 1131 5677 1574 1130 5678 1575 1131 5679 1574 1133 5680 1572 1132 5681 1573 1091 5682 1576 1094 5683 1577 1093 5684 1578 1091 5685 1576 1093 5686 1578 1092 5687 1579 1095 5688 1581 1093 5689 1578 1096 5690 1580 1093 5691 1578 1095 5692 1581 1092 5693 1579 1088 5694 1582 1097 5695 1583 1089 5696 1584 1099 5697 1585 1098 5698 1586 1095 5699 1581 1099 5700 1585 1095 5701 1581 1096 5702 1580 1103 5703 1588 1101 5704 1590 1100 5705 1587 1101 5706 1590 1103 5707 1588 1102 5708 1589 1099 5709 1585 1105 5710 1592 1098 5711 1586 1105 5712 1592 1099 5713 1585 1106 5714 1591 1103 5715 1588 1107 5716 1593 1108 5717 1594 1107 5718 1593 1103 5719 1588 1100 5720 1587 1109 5721 1596 1097 5722 1583 1110 5723 1595 1109 5724 1596 1089 5725 1584 1097 5726 1583 1112 5727 1598 1107 5728 1593 1111 5729 1597 1107 5730 1593 1112 5731 1598 1108 5732 1594 1113 5733 1599 1114 5734 1600 1112 5735 1598 1113 5736 1599 1112 5737 1598 1111 5738 1597 1104 5739 1601 1115 5740 1602 1090 5741 1603 1117 5742 1606 1110 5743 1604 1116 5744 1605 1110 5745 1604 1117 5746 1606 1109 5747 1607 1117 5748 1608 1115 5749 1602 1104 5750 1601 1115 5751 1602 1117 5752 1608 1116 5753 1609 1101 5754 1590 1102 5755 1589 1091 5756 1576 1102 5757 1589 1094 5758 1577 1091 5759 1576 1105 5760 1592 1106 5761 1591 1113 5762 1599 1106 5763 1591 1114 5764 1600 1113 5765 1599 1097 5766 1612 1088 5767 1613 1092 5768 1610 1097 5769 1612 1092 5770 1610 1095 5771 1611 1113 5772 1614 1111 5773 1615 1116 5774 1616 1102 5775 1618 1068 5776 1620 1069 5777 1617 1068 5778 1620 1102 5779 1618 1103 5780 1619 1108 5781 1621 1068 5782 1620 1103 5783 1619 1108 5784 1621 1077 5785 1622 1068 5786 1620 1076 5787 1624 1108 5788 1621 1112 5789 1623 1108 5790 1621 1076 5791 1624 1077 5792 1622 1112 5793 1623 1114 5794 1625 1076 5795 1624 1076 5796 1624 1114 5797 1625 1075 5798 1626 1114 5799 1625 1106 5800 1627 1075 5801 1626 1075 5802 1626 1106 5803 1627 1074 5804 1628 1073 5805 1630 1106 5806 1627 1099 5807 1629 1106 5808 1627 1073 5809 1630 1074 5810 1628 1099 5811 1629 1096 5812 1631 1073 5813 1630 1073 5814 1630 1096 5815 1631 1072 5816 1632 1096 5817 1631 1071 5818 1634 1072 5819 1632 1071 5820 1634 1096 5821 1631 1093 5822 1633 1094 5823 1635 1071 5824 1634 1093 5825 1633 1070 5826 1636 1071 5827 1634 1094 5828 1635 1094 5829 1635 1102 5830 1618 1070 5831 1636 1070 5832 1636 1102 5833 1618 1069 5834 1617 1097 5835 1612 1098 5836 1638 1110 5837 1637 1098 5838 1638 1097 5839 1612 1095 5840 1611 1110 5841 1637 1098 5842 1638 1105 5843 1639 1116 5844 1616 1110 5845 1637 1113 5846 1614 1113 5847 1614 1110 5848 1637 1105 5849 1639 1116 5850 1616 1111 5851 1615 1115 5852 1641 1111 5853 1615 1107 5854 1640 1115 5855 1641 1090 5856 1642 1100 5857 1643 1101 5858 1644 1091 5859 1645 1092 5860 1610 1088 5861 1613 1115 5862 1641 1100 5863 1643 1090 5864 1642 1100 5865 1643 1115 5866 1641 1107 5867 1640 1091 5868 1645 1090 5869 1642 1101 5870 1644 1088 5871 1613 1090 5872 1642 1091 5873 1645 1079 5874 1649 1118 5875 1647 1119 5876 1648 1118 5877 1647 1079 5878 1649 1078 5879 1646 1079 5880 1649 1120 5881 1650 1080 5882 1651 1120 5883 1650 1079 5884 1649 1119 5885 1648 1121 5886 1652 1080 5887 1651 1120 5888 1650 1081 5889 1653 1080 5890 1651 1121 5891 1652 1082 5892 1655 1121 5893 1652 1122 5894 1654 1121 5895 1652 1082 5896 1655 1081 5897 1653 1082 5898 1655 1123 5899 1656 1083 5900 1657 1123 5901 1656 1082 5902 1655 1122 5903 1654 1123 5904 1656 1084 5905 1659 1083 5906 1657 1084 5907 1659 1123 5908 1656 1124 5909 1658 1085 5910 1661 1084 5911 1659 1125 5912 1660 1084 5913 1659 1124 5914 1658 1125 5915 1660 1085 5916 1661 1126 5917 1662 1086 5918 1663 1126 5919 1662 1085 5920 1661 1125 5921 1660 1126 5922 1662 1087 5923 1665 1086 5924 1663 1087 5925 1665 1126 5926 1662 1127 5927 1664 1118 5928 1647 1087 5929 1665 1127 5930 1664 1078 5931 1646 1087 5932 1665 1118 5933 1647 1118 5934 1666 1128 5935 1667 1119 5936 1668 1129 5937 1669 1119 5938 1668 1128 5939 1667 1119 5940 1668 1129 5941 1669 1120 5942 1670 1120 5943 1670 1129 5944 1669 1121 5945 1671 1122 5946 1672 1121 5947 1671 1130 5948 1575 1121 5949 1671 1129 5950 1669 1130 5951 1575 1123 5952 1673 1130 5953 1575 1131 5954 1574 1130 5955 1575 1123 5956 1673 1122 5957 1672 1123 5958 1673 1131 5959 1574 1124 5960 1674 1125 5961 1675 1124 5962 1674 1132 5963 1573 1124 5964 1674 1131 5965 1574 1132 5966 1573 1125 5967 1675 1132 5968 1573 1126 5969 1676 1133 5970 1572 1126 5971 1676 1132 5972 1573 1126 5973 1676 1133 5974 1572 1127 5975 1677 1133 5976 1572 1118 5977 1666 1127 5978 1677 1118 5979 1666 1133 5980 1572 1128 5981 1667 1133 5982 1572 1130 5983 1575 1128 5984 1667 1128 5985 1667 1130 5986 1575 1129 5987 1669 1135 5988 1679 1145 5989 1680 1134 5990 1678 1144 5991 1681 1134 5992 1678 1145 5993 1680 1145 5994 1680 1135 5995 1679 1146 5996 1683 1135 5997 1679 1136 5998 1682 1146 5999 1683 1137 6000 1684 1147 6001 1685 1136 6002 1682 1146 6003 1683 1136 6004 1682 1147 6005 1685 1147 6006 1685 1137 6007 1684 1148 6008 1687 1137 6009 1684 1138 6010 1686 1148 6011 1687 1148 6012 1687 1138 6013 1686 1149 6014 1689 1138 6015 1686 1139 6016 1688 1149 6017 1689 1140 6018 1691 1150 6019 1692 1139 6020 1690 1149 6021 1693 1139 6022 1690 1150 6023 1692 1150 6024 1692 1140 6025 1691 1151 6026 1695 1140 6027 1691 1141 6028 1694 1151 6029 1695 1142 6030 1696 1152 6031 1697 1141 6032 1694 1151 6033 1695 1141 6034 1694 1152 6035 1697 1153 6036 1699 1142 6037 1696 1143 6038 1698 1142 6039 1696 1153 6040 1699 1152 6041 1697 1144 6042 1681 1143 6043 1698 1134 6044 1678 1143 6045 1698 1144 6046 1681 1153 6047 1699 1193 6048 1702 1195 6049 1700 1192 6050 1701 1195 6051 1700 1193 6052 1702 1194 6053 1703 1156 6054 1706 1154 6055 1704 1155 6056 1705 1154 6057 1704 1156 6058 1706 1157 6059 1707 1156 6060 1706 1158 6061 1708 1159 6062 1709 1158 6063 1708 1156 6064 1706 1155 6065 1705 1088 6066 1582 1089 6067 1584 1160 6068 1710 1161 6069 1711 1162 6070 1712 1158 6071 1708 1159 6072 1709 1158 6073 1708 1162 6074 1712 1164 6075 1714 1166 6076 1716 1163 6077 1713 1166 6078 1716 1164 6079 1714 1165 6080 1715 1167 6081 1717 1162 6082 1712 1161 6083 1711 1162 6084 1712 1167 6085 1717 1168 6086 1718 1166 6087 1716 1169 6088 1719 1163 6089 1713 1169 6090 1719 1166 6091 1716 1170 6092 1720 1089 6093 1584 1171 6094 1721 1160 6095 1710 1160 6096 1710 1171 6097 1721 1172 6098 1722 1169 6099 1719 1174 6100 1724 1173 6101 1723 1174 6102 1724 1169 6103 1719 1170 6104 1720 1174 6105 1724 1175 6106 1725 1173 6107 1723 1175 6108 1725 1174 6109 1724 1176 6110 1726 1104 6111 1601 1090 6112 1603 1177 6113 1727 1179 6114 1730 1172 6115 1728 1171 6116 1729 1172 6117 1728 1179 6118 1730 1178 6119 1731 1179 6120 1733 1177 6121 1727 1178 6122 1732 1177 6123 1727 1179 6124 1733 1104 6125 1601 1154 6126 1736 1157 6127 1737 1165 6128 1734 1154 6129 1736 1165 6130 1734 1164 6131 1735 1175 6132 1740 1176 6133 1741 1168 6134 1738 1175 6135 1740 1168 6136 1738 1167 6137 1739 1088 6138 1613 1160 6139 1743 1155 6140 1742 1155 6141 1742 1160 6142 1743 1158 6143 1744 1175 6144 1745 1178 6145 1746 1173 6146 1747 1134 6147 1749 1165 6148 1751 1135 6149 1748 1165 6150 1751 1134 6151 1749 1166 6152 1750 1170 6153 1753 1166 6154 1750 1134 6155 1749 1134 6156 1749 1143 6157 1752 1170 6158 1753 1170 6159 1753 1142 6160 1754 1174 6161 1755 1142 6162 1754 1170 6163 1753 1143 6164 1752 1176 6165 1757 1174 6166 1755 1142 6167 1754 1176 6168 1757 1142 6169 1754 1141 6170 1756 1168 6171 1759 1141 6172 1756 1140 6173 1758 1141 6174 1756 1168 6175 1759 1176 6176 1757 1168 6177 1759 1139 6178 1760 1162 6179 1761 1139 6180 1760 1168 6181 1759 1140 6182 1758 1159 6183 1763 1139 6184 1760 1138 6185 1762 1159 6186 1763 1162 6187 1761 1139 6188 1760 1137 6189 1764 1159 6190 1763 1138 6191 1762 1159 6192 1763 1137 6193 1764 1156 6194 1765 1157 6195 1767 1156 6196 1765 1137 6197 1764 1137 6198 1764 1136 6199 1766 1157 6200 1767 1165 6201 1751 1136 6202 1766 1135 6203 1748 1136 6204 1766 1165 6205 1751 1157 6206 1767 1161 6207 1769 1160 6208 1743 1172 6209 1768 1160 6210 1743 1161 6211 1769 1158 6212 1744 1172 6213 1768 1167 6214 1770 1161 6215 1769 1172 6216 1768 1178 6217 1746 1175 6218 1745 1172 6219 1768 1175 6220 1745 1167 6221 1770 1178 6222 1746 1177 6223 1771 1173 6224 1747 1173 6225 1747 1177 6226 1771 1169 6227 1772 1090 6228 1642 1164 6229 1773 1163 6230 1774 1154 6231 1775 1088 6232 1613 1155 6233 1742 1177 6234 1771 1163 6235 1774 1169 6236 1772 1163 6237 1774 1177 6238 1771 1090 6239 1642 1154 6240 1775 1090 6241 1642 1088 6242 1613 1090 6243 1642 1154 6244 1775 1164 6245 1773 1180 6246 1779 1145 6247 1777 1181 6248 1778 1145 6249 1777 1180 6250 1779 1144 6251 1776 1146 6252 1780 1182 6253 1781 1145 6254 1777 1145 6255 1777 1182 6256 1781 1181 6257 1778 1146 6258 1780 1183 6259 1783 1182 6260 1781 1183 6261 1783 1146 6262 1780 1147 6263 1782 1183 6264 1783 1148 6265 1784 1184 6266 1785 1148 6267 1784 1183 6268 1783 1147 6269 1782 1149 6270 1786 1185 6271 1787 1148 6272 1784 1148 6273 1784 1185 6274 1787 1184 6275 1785 1150 6276 1788 1185 6277 1787 1149 6278 1786 1185 6279 1787 1150 6280 1788 1186 6281 1789 1150 6282 1788 1151 6283 1790 1187 6284 1791 1150 6285 1788 1187 6286 1791 1186 6287 1789 1187 6288 1791 1151 6289 1790 1188 6290 1793 1151 6291 1790 1152 6292 1792 1188 6293 1793 1153 6294 1794 1188 6295 1793 1152 6296 1792 1188 6297 1793 1153 6298 1794 1189 6299 1795 1153 6300 1794 1180 6301 1779 1189 6302 1795 1180 6303 1779 1153 6304 1794 1144 6305 1776 1180 6306 1796 1181 6307 1797 1190 6308 1798 1182 6309 1799 1191 6310 1800 1181 6311 1797 1181 6312 1797 1191 6313 1800 1190 6314 1798 1182 6315 1799 1183 6316 1801 1191 6317 1800 1192 6318 1701 1191 6319 1800 1183 6320 1801 1183 6321 1801 1184 6322 1802 1192 6323 1701 1185 6324 1803 1192 6325 1701 1184 6326 1802 1192 6327 1701 1185 6328 1803 1193 6329 1702 1185 6330 1803 1186 6331 1804 1193 6332 1702 1194 6333 1703 1193 6334 1702 1186 6335 1804 1194 6336 1703 1186 6337 1804 1187 6338 1805 1187 6339 1805 1188 6340 1806 1194 6341 1703 1195 6342 1700 1188 6343 1806 1189 6344 1807 1188 6345 1806 1195 6346 1700 1194 6347 1703 1195 6348 1700 1180 6349 1796 1190 6350 1798 1180 6351 1796 1195 6352 1700 1189 6353 1807 1190 6354 1798 1191 6355 1800 1192 6356 1701 1190 6357 1798 1192 6358 1701 1195 6359 1700 1204 6360 1811 1196 6361 1808 1205 6362 1810 1196 6363 1808 1197 6364 1809 1205 6365 1810 1205 6366 1810 1197 6367 1809 1206 6368 1813 1197 6369 1809 1198 6370 1812 1206 6371 1813 1207 6372 1816 1198 6373 1814 1199 6374 1815 1198 6375 1814 1207 6376 1816 1206 6377 1817 1208 6378 1819 1199 6379 1815 1200 6380 1818 1199 6381 1815 1208 6382 1819 1207 6383 1816 1208 6384 1823 1200 6385 1820 1209 6386 1822 1200 6387 1820 1201 6388 1821 1209 6389 1822 1209 6390 1822 1201 6391 1821 1210 6392 1825 1201 6393 1821 1202 6394 1824 1210 6395 1825 1210 6396 1829 1202 6397 1826 1211 6398 1828 1202 6399 1826 1203 6400 1827 1211 6401 1828 1211 6402 1828 1203 6403 1827 1204 6404 1831 1203 6405 1827 1196 6406 1830 1204 6407 1831 1212 6408 1834 1215 6409 1835 1216 6410 1832 1212 6411 1834 1216 6412 1832 1214 6413 1833 1226 6414 1836 1223 6415 1837 1259 6416 1838 1215 6417 1839 1212 6418 1840 1228 6419 1841 1215 6420 1839 1228 6421 1841 1227 6422 1842 1228 6423 1844 1230 6424 1845 1227 6425 1843 1227 6426 1843 1230 6427 1845 1229 6428 1846 1234 6429 1848 1285 6430 1850 1232 6431 1847 1285 6432 1850 1234 6433 1848 1284 6434 1849 1236 6435 1851 1284 6436 1849 1234 6437 1848 1284 6438 1849 1236 6439 1851 1283 6440 1852 1238 6441 1853 1282 6442 1854 1236 6443 1851 1283 6444 1852 1236 6445 1851 1282 6446 1854 1301 6447 3818 1302 6448 3816 1300 6449 1855 1303 6450 1858 1300 6451 1855 1302 6452 3816 1272 6453 1860 1280 6454 1861 1240 6455 1859 1281 6456 1862 1240 6457 1859 1280 6458 1861 1241 6459 1864 1243 6460 1863 1215 6461 1835 1215 6462 1835 1243 6463 1863 1216 6464 1832 1217 6465 1868 1239 6466 1865 1270 6467 1867 1239 6468 1865 1273 6469 1866 1270 6470 1867 1221 6471 1872 2224 6472 3843 2225 6473 3844 2224 6474 3843 1221 6475 1872 1237 6476 1869 1220 6477 1874 1235 6478 1873 1221 6479 1872 1235 6480 1873 1237 6481 1869 1221 6482 1872 1220 6483 1874 1233 6484 1875 1235 6485 1873 1233 6486 1875 1220 6487 1874 1219 6488 1876 1219 6489 1876 1231 6490 1877 1233 6491 1875 1231 6492 1877 1219 6493 1876 1222 6494 1878 1224 6495 1880 1232 6496 1847 1225 6497 1879 1232 6498 1847 1224 6499 1880 1234 6500 1848 1223 6501 1881 1234 6502 1848 1224 6503 1880 1234 6504 1848 1223 6505 1881 1236 6506 1851 1236 6507 1851 1223 6508 1881 1238 6509 1853 1223 6510 1881 1226 6511 1882 1238 6512 1853 2211 6513 3824 1218 6514 1883 2210 6515 3822 2210 6516 3822 1218 6517 1883 1240 6518 1884 1240 6519 1859 1218 6520 1885 1272 6521 1860 1218 6522 1885 1271 6523 1886 1272 6524 1860 1213 6525 1890 1266 6526 1887 1242 6527 1889 1242 6528 1889 1266 6529 1887 1267 6530 1888 1245 6531 1894 1260 6532 1891 1241 6533 1893 1241 6534 1893 1260 6535 1891 1243 6536 1892 1225 6537 1879 1247 6538 1896 1246 6539 1895 1247 6540 1896 1225 6541 1879 1232 6542 1847 1232 6543 1847 1286 6544 1897 1247 6545 1896 1286 6546 1897 1232 6547 1847 1285 6548 1850 1248 6549 1899 1222 6550 1878 1249 6551 1898 1222 6552 1878 1248 6553 1899 1231 6554 1877 1432 6555 1901 1227 6556 1842 1431 6557 1900 1227 6558 1842 1432 6559 1901 1215 6560 1839 1227 6561 1904 1250 6562 1902 1431 6563 1903 1250 6564 1902 1227 6565 1904 1229 6566 1905 1229 6567 1908 1251 6568 1906 1250 6569 1907 1251 6570 1906 1229 6571 1908 1230 6572 1909 1228 6573 1910 1252 6574 1911 1251 6575 1912 1228 6576 1910 1251 6577 1912 1230 6578 1913 1228 6579 1841 1253 6580 1914 1252 6581 1915 1253 6582 1914 1228 6583 1841 1212 6584 1840 1253 6585 1919 1212 6586 1916 1254 6587 1918 1212 6588 1916 1214 6589 1917 1254 6590 1918 1216 6591 1921 1254 6592 1923 1214 6593 1920 1254 6594 1923 1216 6595 1921 1255 6596 1922 1243 6597 1924 1255 6598 1922 1216 6599 1921 1255 6600 1922 1243 6601 1924 1256 6602 1925 1259 6603 1838 1218 6604 1926 2211 6605 3823 1259 6606 1838 2211 6607 3823 2213 6608 3826 1259 6609 1838 2213 6610 3826 1226 6611 1836 1259 6612 1838 1271 6613 1927 1218 6614 1926 1264 6615 1929 1257 6616 1931 1269 6617 1928 1257 6618 1931 1264 6619 1929 1258 6620 1930 1224 6621 1932 1259 6622 1838 1223 6623 1837 1259 6624 1838 1225 6625 1933 1246 6626 1934 1224 6627 1932 1225 6628 1933 1259 6629 1838 1261 6630 1936 1288 6631 1937 1244 6632 1935 1289 6633 1938 1244 6634 1935 1288 6635 1937 1269 6636 1940 1257 6637 1941 1261 6638 1939 1262 6639 1942 1261 6640 1939 1257 6641 1941 1256 6642 1944 1260 6643 1891 1263 6644 1943 1260 6645 1891 1256 6646 1944 1243 6647 1892 1287 6648 1948 1261 6649 1946 1262 6650 1947 1261 6651 1946 1287 6652 1948 1288 6653 1945 1278 6654 1952 1242 6655 1949 1289 6656 1951 1289 6657 1951 1242 6658 1949 1244 6659 1950 1242 6660 1955 1261 6661 1939 1244 6662 1954 1261 6663 1939 1242 6664 1955 1267 6665 1953 1267 6666 1888 1266 6667 1887 1268 6668 1957 1266 6669 1887 1265 6670 1956 1268 6671 1957 1269 6672 1928 1268 6673 1959 1265 6674 1958 1269 6675 1928 1265 6676 1958 1264 6677 1929 1213 6678 1960 1259 6679 1838 1266 6680 1961 1261 6681 1939 1267 6682 1953 1268 6683 1962 1261 6684 1939 1268 6685 1962 1269 6686 1940 1275 6687 1963 1259 6688 1838 1213 6689 1960 1275 6690 1965 1213 6691 1890 1276 6692 1964 1276 6693 1964 1213 6694 1890 1242 6695 1889 1242 6696 1889 1278 6697 1966 1276 6698 1964 1279 6699 1967 1276 6700 1964 1278 6701 1966 1277 6702 1969 1241 6703 1864 1274 6704 1968 1274 6705 1968 1241 6706 1864 1215 6707 1835 1273 6708 1866 1274 6709 1968 1270 6710 1867 1274 6711 1968 1273 6712 1866 1277 6713 1969 1316 6714 1972 1317 6715 1973 1314 6716 1970 1314 6717 1970 1315 6718 1971 1316 6719 1972 1271 6720 1886 1276 6721 1964 1272 6722 1860 1276 6723 1964 1271 6724 1886 1275 6725 1965 1271 6726 1927 1259 6727 1838 1275 6728 1963 1278 6729 1966 1277 6730 1969 1279 6731 1967 1277 6732 1969 1278 6733 1966 1241 6734 1864 1280 6735 1861 1273 6736 1866 1281 6737 1862 1239 6738 1865 1281 6739 1862 1273 6740 1866 1302 6741 3816 1304 6742 3817 1303 6743 1858 1305 6744 1975 1303 6745 1858 1304 6746 3817 1282 6747 1854 1237 6748 1869 1283 6749 1852 1235 6750 1873 1283 6751 1852 1237 6752 1869 1283 6753 1852 1233 6754 1875 1284 6755 1849 1233 6756 1875 1283 6757 1852 1235 6758 1873 1284 6759 1849 1231 6760 1877 1285 6761 1850 1231 6762 1877 1284 6763 1849 1233 6764 1875 1285 6765 1850 1248 6766 1899 1286 6767 1897 1248 6768 1899 1285 6769 1850 1231 6770 1877 1263 6771 1977 1288 6772 1945 1287 6773 1948 1288 6774 1945 1263 6775 1977 1260 6776 1976 1288 6777 1937 1260 6778 1978 1289 6779 1938 1245 6780 1979 1289 6781 1938 1260 6782 1978 1241 6783 1981 1278 6784 1952 1245 6785 1980 1245 6786 1980 1278 6787 1952 1289 6788 1951 1291 6789 1982 1290 6790 1983 1272 6791 1860 1272 6792 1860 1276 6793 1964 1291 6794 1982 1276 6795 1964 1279 6796 1967 1292 6797 1984 1276 6798 1964 1292 6799 1984 1291 6800 1982 1293 6801 1985 1279 6802 1967 1280 6803 1861 1279 6804 1967 1293 6805 1985 1292 6806 1984 1280 6807 1861 1272 6808 1860 1293 6809 1985 1293 6810 1985 1272 6811 1860 1290 6812 1983 1295 6813 1986 2210 6814 3822 1240 6815 1884 1295 6816 1986 1281 6817 1988 1296 6818 1989 1281 6819 1988 1295 6820 1986 1240 6821 1884 1282 6822 1854 1238 6823 1853 1294 6824 1987 1282 6825 1854 1294 6826 1987 1297 6827 1990 1298 6828 1991 1296 6829 1989 1281 6830 1988 1281 6831 1988 1239 6832 1870 1298 6833 1991 1299 6834 1992 2224 6835 3843 1237 6836 1869 1282 6837 1854 1299 6838 1992 1237 6839 1869 1299 6840 1992 1282 6841 1854 1297 6842 1990 1300 6843 1996 1295 6844 1994 1301 6845 1995 1295 6846 1994 1300 6847 1996 1294 6848 1993 1302 6849 1857 1301 6850 1856 1295 6851 1986 1295 6852 1986 1296 6853 1989 1302 6854 1857 1303 6855 2000 1294 6856 1998 1300 6857 1999 1294 6858 1998 1303 6859 2000 1297 6860 1997 1304 6861 1974 1302 6862 1857 1296 6863 1989 1296 6864 1989 1298 6865 1991 1304 6866 1974 1305 6867 2003 1304 6868 2004 1298 6869 2001 1305 6870 2003 1298 6871 2001 1299 6872 2002 1303 6873 2000 1305 6874 2006 1299 6875 2005 1299 6876 2005 1297 6877 1997 1303 6878 2000 1307 6879 2009 1306 6880 2010 1290 6881 2007 1290 6882 2007 1291 6883 2008 1307 6884 2009 1308 6885 2013 1307 6886 2014 1291 6887 2011 1291 6888 2011 1292 6889 2012 1308 6890 2013 1309 6891 2017 1292 6892 2015 1293 6893 2016 1292 6894 2015 1309 6895 2017 1308 6896 2018 1309 6897 2022 1290 6898 2020 1306 6899 2021 1290 6900 2020 1309 6901 2022 1293 6902 2019 1307 6903 2024 1310 6904 2026 1306 6905 2023 1310 6906 2026 1307 6907 2024 1311 6908 2025 1311 6909 2025 1307 6910 2024 1312 6911 2028 1307 6912 2024 1308 6913 2027 1312 6914 2028 1313 6915 2030 1308 6916 2027 1309 6917 2029 1308 6918 2027 1313 6919 2030 1312 6920 2028 1306 6921 2023 1313 6922 2030 1309 6923 2029 1313 6924 2030 1306 6925 2023 1310 6926 2026 1315 6927 2033 1314 6928 2034 1310 6929 2031 1310 6930 2031 1311 6931 2032 1315 6932 2033 1316 6933 2037 1315 6934 2038 1311 6935 2035 1311 6936 2035 1312 6937 2036 1316 6938 2037 1317 6939 2041 1312 6940 2039 1313 6941 2040 1312 6942 2039 1317 6943 2041 1316 6944 2042 1314 6945 2045 1317 6946 2046 1313 6947 2043 1313 6948 2043 1310 6949 2044 1314 6950 2045 1318 6951 2049 1322 6952 2047 1321 6953 2048 1322 6954 2047 1318 6955 2049 1320 6956 2050 1332 6957 2051 1259 6958 1838 1329 6959 2052 1334 6960 2055 1321 6961 2053 1333 6962 2054 1318 6963 2056 1321 6964 2053 1334 6965 2055 1334 6966 2060 1333 6967 2057 1336 6968 2059 1333 6969 2057 1335 6970 2058 1336 6971 2059 1374 6972 2063 1340 6973 2064 1338 6974 2061 1338 6975 2061 1375 6976 2062 1374 6977 2063 1373 6978 2065 1342 6979 2066 1340 6980 2064 1340 6981 2064 1374 6982 2063 1373 6983 2065 1342 6984 2066 1373 6985 2065 1372 6986 2067 1342 6987 2066 1372 6988 2067 1344 6989 2068 1388 6990 2069 1391 6991 2070 1390 6992 3819 1388 6993 2069 1390 6994 3819 1389 6995 3821 1346 6996 2073 1371 6997 2074 1370 6998 2075 1346 6999 2073 1370 7000 2075 1362 7001 2076 1321 7002 2048 1349 7003 2077 1347 7004 2078 1349 7005 2077 1321 7006 2048 1322 7007 2047 1360 7008 2081 1345 7009 2079 1323 7010 2080 1345 7011 2079 1360 7012 2081 1363 7013 2082 2221 7014 3839 1345 7015 2086 2220 7016 3837 1345 7017 2086 2221 7018 3839 1323 7019 2085 1326 7020 2088 1327 7021 2084 1341 7022 2087 1341 7023 2087 1327 7024 2084 1343 7025 2083 1341 7026 2087 1339 7027 2089 1326 7028 2088 1339 7029 2089 1325 7030 2090 1326 7031 2088 1339 7032 2089 1337 7033 2091 1325 7034 2090 1337 7035 2091 1328 7036 2092 1325 7037 2090 1330 7038 2094 1331 7039 2093 1340 7040 2064 1331 7041 2093 1338 7042 2061 1340 7043 2064 1329 7044 2095 1330 7045 2094 1342 7046 2066 1330 7047 2094 1340 7048 2064 1342 7049 2066 1344 7050 2068 1329 7051 2095 1342 7052 2066 1329 7053 2095 1344 7054 2068 1332 7055 2096 1344 7056 2068 2216 7057 3831 1332 7058 2096 1332 7059 2096 2216 7060 3831 2217 7061 3832 1346 7062 2073 1362 7063 2076 1324 7064 2099 1324 7065 2099 1362 7066 2076 1361 7067 2100 1348 7068 2103 1356 7069 2101 1319 7070 2102 1356 7071 2101 1348 7072 2103 1357 7073 2104 1347 7074 2107 1352 7075 2105 1351 7076 2106 1347 7077 2107 1349 7078 2108 1352 7079 2105 1247 7080 1896 1338 7081 2061 1246 7082 1895 1331 7083 2093 1246 7084 1895 1338 7085 2061 1375 7086 2062 1338 7087 2061 1247 7088 1896 1247 7089 1896 1286 7090 1897 1375 7091 2062 1337 7092 2091 1248 7093 1899 1249 7094 1898 1337 7095 2091 1249 7096 1898 1328 7097 2092 1432 7098 1901 1333 7099 2054 1321 7100 2053 1333 7101 2054 1432 7102 1901 1431 7103 1900 1431 7104 1903 1335 7105 2109 1333 7106 2110 1335 7107 2109 1431 7108 1903 1250 7109 1902 1250 7110 1907 1336 7111 2111 1335 7112 2112 1336 7113 2111 1250 7114 1907 1251 7115 1906 1336 7116 2114 1252 7117 1911 1334 7118 2113 1252 7119 1911 1336 7120 2114 1251 7121 1912 1253 7122 1914 1334 7123 2055 1252 7124 1915 1334 7125 2055 1253 7126 1914 1318 7127 2056 1253 7128 1919 1320 7129 2116 1318 7130 2115 1320 7131 2116 1253 7132 1919 1254 7133 1918 1320 7134 2117 1254 7135 1923 1255 7136 1922 1320 7137 2117 1255 7138 1922 1322 7139 2118 1322 7140 2118 1255 7141 1922 1256 7142 1925 1322 7143 2118 1256 7144 1925 1349 7145 2119 1259 7146 1838 1332 7147 2051 2217 7148 3833 1259 7149 1838 2217 7150 3833 2215 7151 3830 1259 7152 1838 2215 7153 3830 1324 7154 2120 1259 7155 1838 1324 7156 2120 1361 7157 2121 1258 7158 1930 1359 7159 2122 1257 7160 1931 1359 7161 2122 1258 7162 1930 1354 7163 2123 1330 7164 2124 1329 7165 2052 1259 7166 1838 1259 7167 1838 1246 7168 1934 1331 7169 2125 1330 7170 2124 1259 7171 1838 1331 7172 2125 1350 7173 2126 1377 7174 2127 1376 7175 2128 1350 7176 2126 1376 7177 2128 1353 7178 2129 1257 7179 1941 1359 7180 2131 1353 7181 2130 1353 7182 2130 1262 7183 1942 1257 7184 1941 1352 7185 2105 1256 7186 1944 1263 7187 1943 1256 7188 1944 1352 7189 2105 1349 7190 2108 1287 7191 1948 1262 7192 1947 1376 7193 2132 1376 7194 2132 1262 7195 1947 1353 7196 2133 1377 7197 2136 1348 7198 2134 1368 7199 2135 1348 7200 2134 1377 7201 2136 1350 7202 2137 1348 7203 2139 1353 7204 2130 1357 7205 2138 1353 7206 2130 1348 7207 2139 1350 7208 2140 1357 7209 2104 1358 7210 2141 1356 7211 2101 1356 7212 2101 1358 7213 2141 1355 7214 2142 1359 7215 2122 1355 7216 2143 1358 7217 2144 1355 7218 2143 1359 7219 2122 1354 7220 2123 1319 7221 2145 1356 7222 2146 1259 7223 1838 1353 7224 2130 1358 7225 2147 1357 7226 2138 1353 7227 2130 1359 7228 2131 1358 7229 2147 1365 7230 2148 1319 7231 2145 1259 7232 1838 1365 7233 2150 1366 7234 2149 1319 7235 2102 1366 7236 2149 1348 7237 2103 1319 7238 2102 1368 7239 2152 1366 7240 2149 1369 7241 2151 1366 7242 2149 1368 7243 2152 1348 7244 2103 1367 7245 2154 1364 7246 2153 1347 7247 2078 1364 7248 2153 1321 7249 2048 1347 7250 2078 1363 7251 2082 1364 7252 2153 1367 7253 2154 1364 7254 2153 1363 7255 2082 1360 7256 2081 1405 7257 2156 1404 7258 2157 1402 7259 2155 1402 7260 2155 1404 7261 2157 1403 7262 2158 1362 7263 2076 1366 7264 2149 1361 7265 2100 1361 7266 2100 1366 7267 2149 1365 7268 2150 1361 7269 2121 1365 7270 2148 1259 7271 1838 1367 7272 2154 1368 7273 2152 1369 7274 2151 1368 7275 2152 1367 7276 2154 1347 7277 2078 1370 7278 2075 1363 7279 2082 1367 7280 2154 1370 7281 2075 1367 7282 2154 1369 7283 2151 1363 7284 2082 1371 7285 2074 1345 7286 2079 1371 7287 2074 1363 7288 2082 1370 7289 2075 1391 7290 2070 1393 7291 2159 1392 7292 2160 1391 7293 2070 1392 7294 2160 1390 7295 3819 1373 7296 2065 1341 7297 2087 1343 7298 2083 1373 7299 2065 1343 7300 2083 1372 7301 2067 1341 7302 2087 1373 7303 2065 1374 7304 2063 1374 7305 2063 1339 7306 2089 1341 7307 2087 1339 7308 2089 1374 7309 2063 1375 7310 2062 1375 7311 2062 1337 7312 2091 1339 7313 2089 1337 7314 2091 1375 7315 2062 1286 7316 1897 1286 7317 1897 1248 7318 1899 1337 7319 2091 1287 7320 1948 1352 7321 2161 1263 7322 1977 1352 7323 2161 1287 7324 1948 1376 7325 2132 1377 7326 2127 1351 7327 2162 1352 7328 2163 1377 7329 2127 1352 7330 2163 1376 7331 2128 1347 7332 2164 1377 7333 2136 1368 7334 2135 1377 7335 2136 1347 7336 2164 1351 7337 2165 1379 7338 2167 1362 7339 2076 1378 7340 2166 1366 7341 2149 1362 7342 2076 1379 7343 2167 1380 7344 2168 1366 7345 2149 1379 7346 2167 1369 7347 2151 1366 7348 2149 1380 7349 2168 1370 7350 2075 1369 7351 2151 1381 7352 2169 1381 7353 2169 1369 7354 2151 1380 7355 2168 1362 7356 2076 1370 7357 2075 1381 7358 2169 1362 7359 2076 1381 7360 2169 1378 7361 2166 1344 7362 2068 1382 7363 2170 2216 7364 3831 1371 7365 2173 1383 7366 2171 1384 7367 2172 1383 7368 2171 1371 7369 2173 1346 7370 2097 1385 7371 2174 1382 7372 2170 1372 7373 2067 1344 7374 2068 1372 7375 2067 1382 7376 2170 1386 7377 2175 1371 7378 2173 1384 7379 2172 1371 7380 2173 1386 7381 2175 1345 7382 2086 1345 7383 2086 1386 7384 2175 2220 7385 3837 1387 7386 2176 1372 7387 2067 1343 7388 2083 1372 7389 2067 1387 7390 2176 1385 7391 2174 1388 7392 2178 1383 7393 2180 1382 7394 2177 1383 7395 2180 1388 7396 2178 1389 7397 2179 1389 7398 2072 1384 7399 2172 1383 7400 2171 1384 7401 2172 1389 7402 2072 1390 7403 2071 1391 7404 2182 1388 7405 2183 1385 7406 2181 1385 7407 2181 1388 7408 2183 1382 7409 2184 1392 7410 3820 1384 7411 2172 1390 7412 2071 1384 7413 2172 1392 7414 3820 1386 7415 2175 1393 7416 2187 1386 7417 2185 1392 7418 2186 1386 7419 2185 1393 7420 2187 1387 7421 2188 1391 7422 2182 1387 7423 2189 1393 7424 2190 1387 7425 2189 1391 7426 2182 1385 7427 2181 1394 7428 2192 1395 7429 2193 1378 7430 2191 1378 7431 2191 1395 7432 2193 1379 7433 2194 1396 7434 2197 1379 7435 2195 1395 7436 2196 1379 7437 2195 1396 7438 2197 1380 7439 2198 1381 7440 2202 1396 7441 2200 1397 7442 2201 1396 7443 2200 1381 7444 2202 1380 7445 2199 1397 7446 2204 1394 7447 2205 1381 7448 2203 1381 7449 2203 1394 7450 2205 1378 7451 2206 1398 7452 2208 1395 7453 2210 1394 7454 2207 1395 7455 2210 1398 7456 2208 1399 7457 2209 1400 7458 2211 1395 7459 2210 1399 7460 2209 1396 7461 2212 1395 7462 2210 1400 7463 2211 1401 7464 2213 1397 7465 2214 1396 7466 2212 1401 7467 2213 1396 7468 2212 1400 7469 2211 1394 7470 2207 1397 7471 2214 1401 7472 2213 1394 7473 2207 1401 7474 2213 1398 7475 2208 1402 7476 2216 1403 7477 2217 1398 7478 2215 1398 7479 2215 1403 7480 2217 1399 7481 2218 1403 7482 2220 1404 7483 2221 1399 7484 2219 1399 7485 2219 1404 7486 2221 1400 7487 2222 1401 7488 2226 1400 7489 2223 1405 7490 2225 1405 7491 2225 1400 7492 2223 1404 7493 2224 1405 7494 2228 1402 7495 2229 1401 7496 2227 1401 7497 2227 1402 7498 2229 1398 7499 2230 1406 7500 2234 1205 7501 2232 1407 7502 2233 1205 7503 2232 1406 7504 2234 1204 7505 2231 1408 7506 2236 1407 7507 2233 1205 7508 2232 1205 7509 2232 1206 7510 2235 1408 7511 2236 1207 7512 2237 1408 7513 2236 1206 7514 2235 1408 7515 2236 1207 7516 2237 1409 7517 2238 1207 7518 2237 1208 7519 2239 1410 7520 2240 1207 7521 2237 1410 7522 2240 1409 7523 2238 1411 7524 2242 1410 7525 2240 1208 7526 2239 1208 7527 2239 1209 7528 2241 1411 7529 2242 1412 7530 2244 1209 7531 2241 1210 7532 2243 1209 7533 2241 1412 7534 2244 1411 7535 2242 1210 7536 2243 1211 7537 2245 1413 7538 2246 1210 7539 2243 1413 7540 2246 1412 7541 2244 1204 7542 2231 1413 7543 2246 1211 7544 2245 1413 7545 2246 1204 7546 2231 1406 7547 2234 1415 7548 2248 1428 7549 2249 1414 7550 2247 1429 7551 2250 1414 7552 2247 1428 7553 2249 1416 7554 2252 1415 7555 2248 1417 7556 2251 1415 7557 2248 1414 7558 2247 1417 7559 2251 1417 7560 2251 1418 7561 2254 1416 7562 2252 1418 7563 2254 1417 7564 2251 1419 7565 2253 1421 7566 2255 1418 7567 2254 1419 7568 2253 1418 7569 2254 1421 7570 2255 1420 7571 2256 1421 7572 2255 1422 7573 2258 1420 7574 2256 1422 7575 2258 1421 7576 2255 1423 7577 2257 1423 7578 2257 1425 7579 2259 1422 7580 2258 1422 7581 2258 1425 7582 2259 1424 7583 2260 1427 7584 2261 1424 7585 2260 1425 7586 2259 1426 7587 2262 1424 7588 2260 1427 7589 2261 1427 7590 2261 1428 7591 2249 1426 7592 2262 1428 7593 2249 1427 7594 2261 1429 7595 2250 1430 7596 2263 1422 7597 2258 1424 7598 2260 1422 7599 2258 1430 7600 2263 1420 7601 2256 1417 7602 2266 1406 7603 2264 1407 7604 2265 1406 7605 2264 1417 7606 2266 1414 7607 2267 1419 7608 2269 1407 7609 2265 1408 7610 2268 1407 7611 2265 1419 7612 2269 1417 7613 2266 1421 7614 2272 1408 7615 2270 1409 7616 2271 1408 7617 2270 1421 7618 2272 1419 7619 2273 1423 7620 2275 1409 7621 2271 1410 7622 2274 1409 7623 2271 1423 7624 2275 1421 7625 2272 1425 7626 2278 1410 7627 2276 1411 7628 2277 1410 7629 2276 1425 7630 2278 1423 7631 2279 1427 7632 2281 1411 7633 2277 1412 7634 2280 1411 7635 2277 1427 7636 2281 1425 7637 2278 1427 7638 2285 1412 7639 2282 1429 7640 2284 1412 7641 2282 1413 7642 2283 1429 7643 2284 1429 7644 2284 1413 7645 2283 1414 7646 2287 1413 7647 2283 1406 7648 2286 1414 7649 2287 1277 7650 1969 1273 7651 1866 1199 7652 2288 1277 7653 1969 1199 7654 2288 1198 7655 2289 1198 7656 2289 1197 7657 2290 1277 7658 1969 1196 7659 2291 1277 7660 1969 1197 7661 2290 1277 7662 1969 1196 7663 2291 1279 7664 1967 1279 7665 1967 1203 7666 2292 1280 7667 1861 1203 7668 2292 1279 7669 1967 1196 7670 2291 1203 7671 2292 1202 7672 2293 1280 7673 1861 1280 7674 1861 1201 7675 2294 1273 7676 1866 1201 7677 2294 1280 7678 1861 1202 7679 2293 1201 7680 2294 1200 7681 2295 1273 7682 1866 1200 7683 2295 1199 7684 2288 1273 7685 1866 1420 7686 2256 1430 7687 2263 1418 7688 2254 1430 7689 2263 1416 7690 2252 1418 7691 2254 1426 7692 2262 1430 7693 2263 1424 7694 2260 1430 7695 2263 1426 7696 2262 1428 7697 2249 1430 7698 2263 1428 7699 2249 1415 7700 2248 1430 7701 2263 1415 7702 2248 1416 7703 2252 1259 7704 1838 1355 7705 2296 1354 7706 2297 1265 7707 2298 1259 7708 1838 1264 7709 2299 1266 7710 1961 1259 7711 1838 1265 7712 2298 1259 7713 1838 1356 7714 2146 1355 7715 2296 1259 7716 1838 1354 7717 2297 1258 7718 2300 1264 7719 2299 1259 7720 1838 1258 7721 2300 1274 7722 2301 1215 7723 2302 1432 7724 2303 1432 7725 2303 1221 7726 2304 2225 7727 3845 1432 7728 2303 2225 7729 3845 2223 7730 3842 1432 7731 2303 2223 7732 3842 1217 7733 2305 1220 7734 2306 1221 7735 2304 1432 7736 2303 1219 7737 2307 1220 7738 2306 1432 7739 2303 1222 7740 2308 1219 7741 2307 1432 7742 2303 1249 7743 2309 1222 7744 2308 1432 7745 2303 1217 7746 2305 1270 7747 2310 1432 7748 2303 1270 7749 2310 1274 7750 2301 1432 7751 2303 1360 7752 2311 1323 7753 2312 1432 7754 2303 1432 7755 2303 1323 7756 2312 2221 7757 3838 1432 7758 2303 2221 7759 3838 2219 7760 3835 1432 7761 2303 2219 7762 3835 1327 7763 2313 1327 7764 2313 1326 7765 2314 1432 7766 2303 1326 7767 2314 1325 7768 2315 1432 7769 2303 1325 7770 2315 1328 7771 2316 1432 7772 2303 1328 7773 2316 1249 7774 2309 1432 7775 2303 1321 7776 2317 1364 7777 2318 1432 7778 2303 1364 7779 2318 1360 7780 2311 1432 7781 2303 1434 7782 2321 1435 7783 2322 1441 7784 2319 1441 7785 2319 1440 7786 2320 1434 7787 2321 1442 7788 2324 1437 7789 2326 1443 7790 2323 1437 7791 2326 1442 7792 2324 1436 7793 2325 1438 7794 2329 1433 7795 2330 1439 7796 2327 1438 7797 2329 1439 7798 2327 1444 7799 2328 1441 7800 2332 1446 7801 2334 1440 7802 2331 1446 7803 2334 1441 7804 2332 1447 7805 2333 1442 7806 2335 1443 7807 2336 1449 7808 2337 1442 7809 2335 1449 7810 2337 1448 7811 2338 1450 7812 2342 1439 7813 2340 1445 7814 2341 1439 7815 2340 1450 7816 2342 1444 7817 2339 1447 7818 2344 1452 7819 2346 1446 7820 2343 1452 7821 2346 1447 7822 2344 1453 7823 2345 1454 7824 2350 1449 7825 2348 1455 7826 2349 1449 7827 2348 1454 7828 2350 1448 7829 2347 1451 7830 2353 1450 7831 2351 1445 7832 2352 1450 7833 2351 1451 7834 2353 1456 7835 2354 1465 7836 2357 1458 7837 2355 1459 7838 2356 1458 7839 2355 1465 7840 2357 1464 7841 2358 1466 7842 2362 1461 7843 2360 1467 7844 2361 1461 7845 2360 1466 7846 2362 1460 7847 2359 1462 7848 2363 1457 7849 2364 1463 7850 2365 1462 7851 2363 1463 7852 2365 1468 7853 2366 1465 7854 2368 1470 7855 2370 1464 7856 2367 1470 7857 2370 1465 7858 2368 1471 7859 2369 1467 7860 2372 1472 7861 2374 1466 7862 2371 1472 7863 2374 1467 7864 2372 1473 7865 2373 1469 7866 2377 1474 7867 2378 1468 7868 2375 1468 7869 2375 1463 7870 2376 1469 7871 2377 1477 7872 2381 1470 7873 2379 1471 7874 2380 1470 7875 2379 1477 7876 2381 1476 7877 2382 1479 7878 2385 1478 7879 2386 1472 7880 2383 1479 7881 2385 1472 7882 2383 1473 7883 2384 1469 7884 2388 1480 7885 2390 1474 7886 2387 1480 7887 2390 1469 7888 2388 1475 7889 2389 1481 7890 2391 1484 7891 2392 1483 7892 2393 1482 7893 2394 1486 7894 2395 1485 7895 2396 1496 7896 2398 1502 7897 2400 1495 7898 2397 1502 7899 2400 1496 7900 2398 1501 7901 2399 1506 7902 2404 1500 7903 2402 1505 7904 2403 1500 7905 2402 1506 7906 2404 1499 7907 2401 1433 7908 2330 1483 7909 2393 1439 7910 2327 1483 7911 2393 1433 7912 2330 1481 7913 2391 1434 7914 2321 1484 7915 2406 1481 7916 2405 1484 7917 2406 1434 7918 2321 1440 7919 2320 1485 7920 2408 1435 7921 2322 1482 7922 2407 1435 7923 2322 1485 7924 2408 1441 7925 2319 1486 7926 2395 1436 7927 2325 1442 7928 2324 1436 7929 2325 1486 7930 2395 1482 7931 2394 1439 7932 2340 1483 7933 2409 1487 7934 2410 1439 7935 2340 1487 7936 2410 1445 7937 2341 1446 7938 2334 1484 7939 2411 1440 7940 2331 1484 7941 2411 1446 7942 2334 1488 7943 2412 1447 7944 2333 1485 7945 2413 1489 7946 2414 1485 7947 2413 1447 7948 2333 1441 7949 2332 1490 7950 2416 1442 7951 2335 1448 7952 2338 1442 7953 2335 1490 7954 2416 1486 7955 2415 1487 7956 2417 1491 7957 2418 1445 7958 2352 1445 7959 2352 1491 7960 2418 1451 7961 2353 1446 7962 2343 1491 7963 2420 1488 7964 2419 1491 7965 2420 1446 7966 2343 1452 7967 2346 1492 7968 2422 1447 7969 2344 1489 7970 2421 1447 7971 2344 1492 7972 2422 1453 7973 2345 1492 7974 2424 1448 7975 2347 1454 7976 2350 1448 7977 2347 1492 7978 2424 1490 7979 2423 1494 7980 2425 1495 7981 2426 1457 7982 2364 1457 7983 2364 1495 7984 2426 1463 7985 2365 1458 7986 2355 1464 7987 2358 1496 7988 2427 1458 7989 2355 1496 7990 2427 1493 7991 2428 1499 7992 2430 1459 7993 2356 1498 7994 2429 1459 7995 2356 1499 7996 2430 1465 7997 2357 1466 7998 2362 1500 7999 2431 1460 8000 2359 1500 8001 2431 1497 8002 2432 1460 8003 2359 1495 8004 2397 1469 8005 2377 1463 8006 2376 1469 8007 2377 1495 8008 2397 1502 8009 2400 1464 8010 2367 1501 8011 2399 1496 8012 2398 1501 8013 2399 1464 8014 2367 1470 8015 2370 1471 8016 2369 1499 8017 2401 1506 8018 2404 1499 8019 2401 1471 8020 2369 1465 8021 2368 1505 8022 2403 1466 8023 2371 1472 8024 2374 1466 8025 2371 1505 8026 2403 1500 8027 2402 1502 8028 2433 1504 8029 2434 1469 8030 2388 1469 8031 2388 1504 8032 2434 1475 8033 2389 1476 8034 2382 1501 8035 2435 1470 8036 2379 1501 8037 2435 1476 8038 2382 1503 8039 2436 1508 8040 2438 1471 8041 2380 1506 8042 2437 1471 8043 2380 1508 8044 2438 1477 8045 2381 1478 8046 2386 1507 8047 2440 1505 8048 2439 1478 8049 2386 1505 8050 2439 1472 8051 2383 1484 8052 2442 1495 8053 2397 1483 8054 2441 1495 8055 2397 1484 8056 2442 1496 8057 2398 1483 8058 2444 1495 8059 2426 1487 8060 2443 1487 8061 2443 1495 8062 2426 1494 8063 2425 1488 8064 2446 1496 8065 2427 1484 8066 2445 1496 8067 2427 1488 8068 2446 1493 8069 2428 1499 8070 2401 1485 8071 2447 1500 8072 2402 1485 8073 2447 1486 8074 2448 1500 8075 2402 1490 8076 2450 1500 8077 2431 1486 8078 2449 1500 8079 2431 1490 8080 2450 1497 8081 2432 1485 8082 2452 1499 8083 2430 1489 8084 2451 1489 8085 2451 1499 8086 2430 1498 8087 2429 1503 8088 2454 1509 8089 2455 1501 8090 2453 1510 8091 2456 1501 8092 2453 1509 8093 2455 1502 8094 2458 1512 8095 2460 1504 8096 2457 1512 8097 2460 1502 8098 2458 1511 8099 2459 1501 8100 2399 1510 8101 2461 1502 8102 2400 1511 8103 2462 1502 8104 2400 1510 8105 2461 1506 8106 2464 1509 8107 2455 1508 8108 2463 1509 8109 2455 1506 8110 2464 1510 8111 2456 1510 8112 2461 1505 8113 2403 1513 8114 2465 1505 8115 2403 1510 8116 2461 1506 8117 2404 1507 8118 2467 1514 8119 2468 1505 8120 2466 1513 8121 2469 1505 8122 2466 1514 8123 2468 1521 8124 2473 1516 8125 2471 1520 8126 2472 1516 8127 2471 1521 8128 2473 1517 8129 2470 1437 8130 2326 1522 8131 2475 1443 8132 2323 1522 8133 2475 1437 8134 2326 1518 8135 2474 1438 8136 2329 1519 8137 2477 1515 8138 2476 1519 8139 2477 1438 8140 2329 1444 8141 2328 1521 8142 2481 1524 8143 2479 1525 8144 2480 1524 8145 2479 1521 8146 2481 1520 8147 2478 1526 8148 2483 1449 8149 2337 1522 8150 2482 1443 8151 2336 1522 8152 2482 1449 8153 2337 1450 8154 2342 1519 8155 2485 1444 8156 2339 1519 8157 2485 1450 8158 2342 1523 8159 2484 1525 8160 2489 1528 8161 2487 1529 8162 2488 1528 8163 2487 1525 8164 2489 1524 8165 2486 1449 8166 2348 1530 8167 2491 1455 8168 2349 1530 8169 2491 1449 8170 2348 1526 8171 2490 1523 8172 2493 1450 8173 2351 1527 8174 2492 1450 8175 2351 1456 8176 2354 1527 8177 2492 1533 8178 2497 1532 8179 2494 1537 8180 2496 1537 8181 2496 1532 8182 2494 1536 8183 2495 1538 8184 2499 1461 8185 2360 1534 8186 2498 1461 8187 2360 1538 8188 2499 1467 8189 2361 1468 8190 2366 1535 8191 2500 1462 8192 2363 1531 8193 2501 1462 8194 2363 1535 8195 2500 1537 8196 2505 1540 8197 2503 1541 8198 2504 1540 8199 2503 1537 8200 2505 1536 8201 2502 1542 8202 2507 1467 8203 2372 1538 8204 2506 1467 8205 2372 1542 8206 2507 1473 8207 2373 1539 8208 2508 1468 8209 2375 1474 8210 2378 1468 8211 2375 1539 8212 2508 1535 8213 2509 1541 8214 2513 1540 8215 2510 1545 8216 2512 1545 8217 2512 1540 8218 2510 1544 8219 2511 1546 8220 2515 1473 8221 2384 1542 8222 2514 1473 8223 2384 1546 8224 2515 1479 8225 2385 1480 8226 2390 1543 8227 2516 1474 8228 2387 1539 8229 2517 1474 8230 2387 1543 8231 2516 1547 8232 2518 1549 8233 2519 1550 8234 2520 1548 8235 2521 1551 8236 2522 1552 8237 2523 1568 8238 2525 1562 8239 2527 1561 8240 2524 1562 8241 2527 1568 8242 2525 1567 8243 2526 1572 8244 2529 1566 8245 2531 1565 8246 2528 1566 8247 2531 1572 8248 2529 1571 8249 2530 1547 8250 2518 1515 8251 2476 1549 8252 2519 1515 8253 2476 1519 8254 2477 1549 8255 2519 1516 8256 2471 1550 8257 2533 1520 8258 2472 1550 8259 2533 1516 8260 2471 1547 8261 2532 1548 8262 2535 1517 8263 2470 1551 8264 2534 1551 8265 2534 1517 8266 2470 1521 8267 2473 1518 8268 2474 1552 8269 2523 1522 8270 2475 1552 8271 2523 1518 8272 2474 1548 8273 2521 1553 8274 2536 1519 8275 2485 1523 8276 2484 1549 8277 2537 1519 8278 2485 1553 8279 2536 1520 8280 2478 1550 8281 2538 1524 8282 2479 1550 8283 2538 1554 8284 2539 1524 8285 2479 1551 8286 2541 1525 8287 2480 1555 8288 2540 1525 8289 2480 1551 8290 2541 1521 8291 2481 1556 8292 2543 1522 8293 2482 1552 8294 2542 1522 8295 2482 1556 8296 2543 1526 8297 2483 1557 8298 2544 1553 8299 2545 1523 8300 2493 1523 8301 2493 1527 8302 2492 1557 8303 2544 1524 8304 2486 1557 8305 2547 1528 8306 2487 1557 8307 2547 1524 8308 2486 1554 8309 2546 1558 8310 2548 1555 8311 2549 1525 8312 2489 1558 8313 2548 1525 8314 2489 1529 8315 2488 1526 8316 2490 1558 8317 2551 1530 8318 2491 1558 8319 2551 1526 8320 2490 1556 8321 2550 1560 8322 2553 1531 8323 2501 1561 8324 2552 1531 8325 2501 1535 8326 2500 1561 8327 2552 1532 8328 2494 1562 8329 2554 1536 8330 2495 1562 8331 2554 1532 8332 2494 1559 8333 2555 1565 8334 2556 1564 8335 2557 1533 8336 2497 1565 8337 2556 1533 8338 2497 1537 8339 2496 1538 8340 2499 1534 8341 2498 1566 8342 2558 1566 8343 2558 1534 8344 2498 1563 8345 2559 1539 8346 2508 1561 8347 2524 1535 8348 2509 1561 8349 2524 1539 8350 2508 1568 8351 2525 1536 8352 2502 1567 8353 2526 1540 8354 2503 1567 8355 2526 1536 8356 2502 1562 8357 2527 1565 8358 2528 1541 8359 2504 1572 8360 2529 1541 8361 2504 1565 8362 2528 1537 8363 2505 1571 8364 2530 1538 8365 2506 1566 8366 2531 1538 8367 2506 1571 8368 2530 1542 8369 2507 1568 8370 2561 1539 8371 2517 1570 8372 2560 1539 8373 2517 1543 8374 2516 1570 8375 2560 1544 8376 2511 1540 8377 2510 1567 8378 2562 1544 8379 2511 1567 8380 2562 1569 8381 2563 1574 8382 2564 1572 8383 2565 1541 8384 2513 1574 8385 2564 1541 8386 2513 1545 8387 2512 1573 8388 2567 1542 8389 2514 1571 8390 2566 1542 8391 2514 1573 8392 2567 1546 8393 2515 1550 8394 2569 1561 8395 2524 1562 8396 2527 1561 8397 2524 1550 8398 2569 1549 8399 2568 1561 8400 2552 1553 8401 2570 1560 8402 2553 1561 8403 2552 1549 8404 2571 1553 8405 2570 1562 8406 2554 1554 8407 2573 1550 8408 2572 1554 8409 2573 1562 8410 2554 1559 8411 2555 1566 8412 2531 1551 8413 2574 1565 8414 2528 1551 8415 2574 1566 8416 2531 1552 8417 2575 1566 8418 2558 1556 8419 2577 1552 8420 2576 1556 8421 2577 1566 8422 2558 1563 8423 2559 1565 8424 2556 1555 8425 2578 1564 8426 2557 1565 8427 2556 1551 8428 2579 1555 8429 2578 1567 8430 2580 1576 8431 2581 1575 8432 2582 1567 8433 2580 1575 8434 2582 1569 8435 2583 1512 8436 2460 1568 8437 2585 1570 8438 2584 1568 8439 2585 1512 8440 2460 1511 8441 2459 1576 8442 2586 1567 8443 2526 1568 8444 2525 1568 8445 2525 1511 8446 2462 1576 8447 2586 1575 8448 2582 1572 8449 2588 1574 8450 2587 1572 8451 2588 1575 8452 2582 1576 8453 2581 1576 8454 2586 1571 8455 2530 1572 8456 2529 1571 8457 2530 1576 8458 2586 1513 8459 2465 1571 8460 2589 1513 8461 2469 1514 8462 2468 1571 8463 2589 1514 8464 2468 1573 8465 2590 1511 8466 2462 1510 8467 2461 1513 8468 2465 1511 8469 2462 1513 8470 2465 1576 8471 2586 1577 8472 2593 1481 8473 2591 1433 8474 2592 1481 8475 2591 1577 8476 2593 1578 8477 2594 1580 8478 2598 1435 8479 2595 1579 8480 2597 1435 8481 2595 1434 8482 2596 1579 8483 2597 1482 8484 2599 1435 8485 2595 1580 8486 2598 1482 8487 2599 1580 8488 2598 1581 8489 2600 1582 8490 2603 1437 8491 2601 1436 8492 2602 1437 8493 2601 1582 8494 2603 1583 8495 2604 1433 8496 2592 1584 8497 2606 1577 8498 2593 1584 8499 2606 1433 8500 2592 1438 8501 2605 1481 8502 2591 1579 8503 2597 1434 8504 2596 1579 8505 2597 1481 8506 2591 1578 8507 2594 1582 8508 2603 1482 8509 2599 1581 8510 2600 1482 8511 2599 1582 8512 2603 1436 8513 2602 1586 8514 2609 1516 8515 2607 1517 8516 2608 1516 8517 2607 1586 8518 2609 1585 8519 2610 1437 8520 2601 1587 8521 2612 1518 8522 2611 1587 8523 2612 1437 8524 2601 1583 8525 2604 1584 8526 2606 1515 8527 2613 1588 8528 2614 1515 8529 2613 1584 8530 2606 1438 8531 2605 1547 8532 2615 1588 8533 2614 1515 8534 2613 1588 8535 2614 1547 8536 2615 1589 8537 2616 1585 8538 2610 1547 8539 2615 1516 8540 2607 1547 8541 2615 1585 8542 2610 1589 8543 2616 1548 8544 2617 1586 8545 2609 1517 8546 2608 1586 8547 2609 1548 8548 2617 1590 8549 2618 1587 8550 2612 1590 8551 2618 1548 8552 2617 1548 8553 2617 1518 8554 2611 1587 8555 2612 1592 8556 2621 1585 8557 2619 1586 8558 2620 1585 8559 2619 1592 8560 2621 1591 8561 2622 1593 8562 2624 1586 8563 2620 1590 8564 2623 1586 8565 2620 1593 8566 2624 1592 8567 2621 1587 8568 2625 1593 8569 2624 1590 8570 2623 1593 8571 2624 1587 8572 2625 1594 8573 2626 1583 8574 2627 1594 8575 2626 1587 8576 2625 1594 8577 2626 1583 8578 2627 1595 8579 2628 1582 8580 2629 1595 8581 2628 1583 8582 2627 1595 8583 2628 1582 8584 2629 1596 8585 2630 1581 8586 2631 1596 8587 2630 1582 8588 2629 1596 8589 2630 1581 8590 2631 1597 8591 2632 1580 8592 2633 1598 8593 2634 1581 8594 2631 1597 8595 2632 1581 8596 2631 1598 8597 2634 1579 8598 2635 1599 8599 2636 1580 8600 2633 1598 8601 2634 1580 8602 2633 1599 8603 2636 1490 8604 2423 1492 8605 2424 1489 8606 2637 1555 8607 2638 1558 8608 2551 1556 8609 2550 1553 8610 2545 1557 8611 2544 1554 8612 2639 1488 8613 2640 1491 8614 2418 1487 8615 2417 1491 8616 2642 1601 8617 2643 1451 8618 2641 1451 8619 2641 1601 8620 2643 1600 8621 2644 1453 8622 2646 1602 8623 2648 1452 8624 2645 1602 8625 2648 1453 8626 2646 1603 8627 2647 1604 8628 2650 1453 8629 2646 1492 8630 2649 1453 8631 2646 1604 8632 2650 1603 8633 2647 1605 8634 2654 1455 8635 2652 1606 8636 2653 1455 8637 2652 1605 8638 2654 1454 8639 2651 1451 8640 2641 1600 8641 2644 1456 8642 2655 1456 8643 2655 1600 8644 2644 1607 8645 2656 1452 8646 2645 1601 8647 2643 1491 8648 2642 1601 8649 2643 1452 8650 2645 1602 8651 2648 1604 8652 2650 1454 8653 2651 1605 8654 2654 1454 8655 2651 1604 8656 2650 1492 8657 2649 1609 8658 2660 1529 8659 2657 1608 8660 2659 1529 8661 2657 1528 8662 2658 1608 8663 2659 1610 8664 2662 1606 8665 2653 1455 8666 2652 1455 8667 2652 1530 8668 2661 1610 8669 2662 1456 8670 2655 1611 8671 2664 1527 8672 2663 1611 8673 2664 1456 8674 2655 1607 8675 2656 1527 8676 2663 1612 8677 2666 1557 8678 2665 1612 8679 2666 1527 8680 2663 1611 8681 2664 1608 8682 2659 1528 8683 2658 1612 8684 2666 1528 8685 2658 1557 8686 2665 1612 8687 2666 1613 8688 2668 1529 8689 2657 1609 8690 2660 1529 8691 2657 1613 8692 2668 1558 8693 2667 1610 8694 2662 1530 8695 2661 1613 8696 2668 1530 8697 2661 1558 8698 2667 1613 8699 2668 1600 8700 2644 1601 8701 2643 1614 8702 2669 1602 8703 2648 1603 8704 2647 1614 8705 2669 1603 8706 2647 1604 8707 2650 1614 8708 2669 1605 8709 2654 1606 8710 2653 1614 8711 2669 1607 8712 2656 1600 8713 2644 1614 8714 2669 1601 8715 2643 1602 8716 2648 1614 8717 2669 1604 8718 2650 1605 8719 2654 1614 8720 2669 1609 8721 2660 1608 8722 2659 1614 8723 2669 1606 8724 2653 1610 8725 2662 1614 8726 2669 1611 8727 2664 1607 8728 2656 1614 8729 2669 1612 8730 2666 1611 8731 2664 1614 8732 2669 1608 8733 2659 1612 8734 2666 1614 8735 2669 1613 8736 2668 1609 8737 2660 1614 8738 2669 1610 8739 2662 1613 8740 2668 1614 8741 2669 1593 8742 2671 1595 8743 2673 1596 8744 2670 1595 8745 2673 1593 8746 2671 1594 8747 2672 1589 8748 2616 1579 8749 2597 1578 8750 2594 1585 8751 2610 1579 8752 2597 1589 8753 2616 1577 8754 2593 1589 8755 2616 1578 8756 2594 1589 8757 2616 1577 8758 2593 1588 8759 2614 1577 8760 2593 1584 8761 2606 1588 8762 2614 1616 8763 2677 1618 8764 2675 1617 8765 2676 1618 8766 2675 1616 8767 2677 1615 8768 2674 1615 8769 2680 1616 8770 2681 1622 8771 2678 1615 8772 2680 1622 8773 2678 1619 8774 2679 1615 8775 2685 1628 8776 2683 1618 8777 2684 1628 8778 2683 1615 8779 2685 1619 8780 2682 1616 8781 2689 1625 8782 2687 1622 8783 2688 1625 8784 2687 1616 8785 2689 1617 8786 2686 1628 8787 2691 1625 8788 2692 1618 8789 2690 1617 8790 2693 1618 8791 2690 1625 8792 2692 1620 8793 2694 1629 8794 2695 1619 8795 2682 1619 8796 2682 1629 8797 2695 1628 8798 2683 1621 8799 2696 1629 8800 2695 1620 8801 2694 1629 8802 2695 1621 8803 2696 1630 8804 2697 1620 8805 2700 1647 8806 2698 1621 8807 2699 1620 8808 2700 1623 8809 2701 1647 8810 2698 1647 8811 2698 1623 8812 2701 1624 8813 2702 1622 8814 2678 1620 8815 2703 1619 8816 2679 1620 8817 2703 1622 8818 2678 1623 8819 2704 1623 8820 2706 1626 8821 2707 1624 8822 2705 1627 8823 2708 1624 8824 2705 1626 8825 2707 1622 8826 2688 1626 8827 2707 1623 8828 2706 1626 8829 2707 1622 8830 2688 1625 8831 2687 1626 8832 2712 1630 8833 2710 1627 8834 2711 1630 8835 2710 1626 8836 2712 1629 8837 2709 1629 8838 2713 1626 8839 2714 1628 8840 2691 1625 8841 2692 1628 8842 2691 1626 8843 2714 1633 8844 2718 1631 8845 2716 1632 8846 2717 1631 8847 2716 1633 8848 2718 1634 8849 2715 1635 8850 2720 1638 8851 2721 1631 8852 2719 1632 8853 2722 1631 8854 2719 1638 8855 2721 1631 8856 2724 1644 8857 2726 1635 8858 2723 1644 8859 2726 1631 8860 2724 1634 8861 2725 1632 8862 2728 1641 8863 2730 1633 8864 2727 1641 8865 2730 1632 8866 2728 1638 8867 2729 1633 8868 2733 1644 8869 2731 1634 8870 2732 1644 8871 2731 1633 8872 2733 1641 8873 2734 1627 8874 2711 1646 8875 2735 1643 8876 2736 1646 8877 2735 1627 8878 2711 1630 8879 2710 1621 8880 2696 1637 8881 2737 1646 8882 2738 1621 8883 2696 1646 8884 2738 1630 8885 2697 1637 8886 2740 1647 8887 2698 1648 8888 2739 1647 8889 2698 1637 8890 2740 1621 8891 2699 1640 8892 2742 1627 8893 2708 1643 8894 2741 1627 8895 2708 1640 8896 2742 1624 8897 2705 1645 8898 2743 1636 8899 2744 1635 8900 2723 1635 8901 2723 1644 8902 2726 1645 8903 2743 1637 8904 2737 1645 8905 2743 1646 8906 2738 1645 8907 2743 1637 8908 2737 1636 8909 2744 1637 8910 2740 1648 8911 2739 1636 8912 2745 1639 8913 2747 1636 8914 2745 1648 8915 2739 1648 8916 2739 1640 8917 2746 1639 8918 2747 1636 8919 2748 1639 8920 2749 1635 8921 2720 1638 8922 2721 1635 8923 2720 1639 8924 2749 1640 8925 2742 1643 8926 2741 1642 8927 2750 1640 8928 2742 1642 8929 2750 1639 8930 2751 1642 8931 2750 1638 8932 2729 1639 8933 2751 1638 8934 2729 1642 8935 2750 1641 8936 2730 1643 8937 2736 1645 8938 2752 1642 8939 2753 1645 8940 2752 1643 8941 2736 1646 8942 2735 1641 8943 2734 1645 8944 2754 1644 8945 2731 1645 8946 2754 1641 8947 2734 1642 8948 2755 1655 8949 2758 1649 8950 2759 1651 8951 2756 1655 8952 2758 1651 8953 2756 1653 8954 2757 1652 8955 2760 1647 8956 2698 1624 8957 2702 1647 8958 2698 1652 8959 2760 1650 8960 2761 1624 8961 2705 1640 8962 2742 1654 8963 2762 1624 8964 2705 1654 8965 2762 1652 8966 2763 1656 8967 2764 1640 8968 2746 1648 8969 2739 1640 8970 2746 1656 8971 2764 1654 8972 2765 1648 8973 2768 1647 8974 2769 1650 8975 2766 1648 8976 2768 1650 8977 2766 1656 8978 2767 1649 8979 2759 1650 8980 2761 1652 8981 2760 1649 8982 2759 1652 8983 2760 1651 8984 2756 1656 8985 2764 1655 8986 2758 1653 8987 2757 1656 8988 2764 1653 8989 2757 1654 8990 2765 1652 8991 2763 1654 8992 2762 1651 8993 2770 1651 8994 2770 1654 8995 2762 1653 8996 2771 1656 8997 2767 1650 8998 2766 1655 8999 2772 1655 9000 2772 1650 9001 2766 1649 9002 2773 1592 9003 2776 1598 9004 2777 1599 9005 2774 1592 9006 2776 1599 9007 2774 1591 9008 2775 1598 9009 2777 1592 9010 2776 1593 9011 2671 1598 9012 2777 1593 9013 2671 1597 9014 2778 1597 9015 2778 1593 9016 2671 1596 9017 2670 1664 9018 2782 1657 9019 2779 1665 9020 2781 1657 9021 2779 1658 9022 2780 1665 9023 2781 1666 9024 2784 1665 9025 2781 1658 9026 2780 1658 9027 2780 1659 9028 2783 1666 9029 2784 1661 9030 2786 1667 9031 2788 1660 9032 2785 1667 9033 2788 1661 9034 2786 1668 9035 2787 1669 9036 2790 1661 9037 2786 1662 9038 2789 1661 9039 2786 1669 9040 2790 1668 9041 2787 1670 9042 2793 1662 9043 2791 1663 9044 2792 1662 9045 2791 1670 9046 2793 1669 9047 2794 1664 9048 2796 1663 9049 2792 1657 9050 2795 1663 9051 2792 1664 9052 2796 1670 9053 2793 1663 9054 2800 1662 9055 2797 1757 9056 2799 1662 9057 2797 1661 9058 2798 1757 9059 2799 1665 9060 2802 1671 9061 2804 1664 9062 2801 1671 9063 2804 1665 9064 2802 1672 9065 2803 1673 9066 2806 1672 9067 2803 1665 9068 2802 1665 9069 2802 1666 9070 2805 1673 9071 2806 1666 9072 2805 1674 9073 2807 1673 9074 2806 1666 9075 2805 1667 9076 2808 1675 9077 2809 1666 9078 2805 1675 9079 2809 1674 9080 2807 1667 9081 2808 1676 9082 2810 1675 9083 2809 1676 9084 2810 1668 9085 2811 1677 9086 2812 1667 9087 2808 1668 9088 2811 1676 9089 2810 1668 9090 2811 1669 9091 2813 1678 9092 2814 1668 9093 2811 1678 9094 2814 1677 9095 2812 1679 9096 2816 1678 9097 2814 1669 9098 2813 1669 9099 2813 1670 9100 2815 1679 9101 2816 1664 9102 2801 1679 9103 2816 1670 9104 2815 1679 9105 2816 1664 9106 2801 1671 9107 2804 1681 9108 2819 1680 9109 2820 1671 9110 2817 1671 9111 2817 1672 9112 2818 1681 9113 2819 1682 9114 2822 1681 9115 2819 1672 9116 2818 1672 9117 2818 1673 9118 2821 1682 9119 2822 1683 9120 2824 1673 9121 2821 1674 9122 2823 1673 9123 2821 1683 9124 2824 1682 9125 2822 1684 9126 2827 1674 9127 2825 1675 9128 2826 1674 9129 2825 1684 9130 2827 1683 9131 2828 1685 9132 2831 1675 9133 2829 1676 9134 2830 1675 9135 2829 1685 9136 2831 1684 9137 2832 1677 9138 2833 1685 9139 2831 1676 9140 2830 1685 9141 2831 1677 9142 2833 1686 9143 2834 1687 9144 2836 1677 9145 2833 1678 9146 2835 1677 9147 2833 1687 9148 2836 1686 9149 2834 1688 9150 2839 1678 9151 2837 1679 9152 2838 1678 9153 2837 1688 9154 2839 1687 9155 2840 1680 9156 2842 1679 9157 2838 1671 9158 2841 1679 9159 2838 1680 9160 2842 1688 9161 2839 1680 9162 2843 1681 9163 2844 1690 9164 2845 1680 9165 2843 1690 9166 2845 1689 9167 2846 1681 9168 2844 1682 9169 2847 1691 9170 2848 1681 9171 2844 1691 9172 2848 1690 9173 2845 1692 9174 2850 1682 9175 2847 1683 9176 2849 1682 9177 2847 1692 9178 2850 1691 9179 2848 1684 9180 2851 1692 9181 2850 1683 9182 2849 1692 9183 2850 1684 9184 2851 1693 9185 2852 1685 9186 2853 1693 9187 2852 1684 9188 2851 1693 9189 2852 1685 9190 2853 1694 9191 2854 1686 9192 2855 1694 9193 2854 1685 9194 2853 1694 9195 2854 1686 9196 2855 1695 9197 2856 1687 9198 2857 1695 9199 2856 1686 9200 2855 1695 9201 2856 1687 9202 2857 1696 9203 2858 1688 9204 2859 1696 9205 2858 1687 9206 2857 1696 9207 2858 1688 9208 2859 1697 9209 2860 1689 9210 2846 1688 9211 2859 1680 9212 2843 1688 9213 2859 1689 9214 2846 1697 9215 2860 1690 9216 2862 1699 9217 2863 1689 9218 2861 1698 9219 2864 1689 9220 2861 1699 9221 2863 1691 9222 2865 1700 9223 2866 1690 9224 2862 1699 9225 2863 1690 9226 2862 1700 9227 2866 1701 9228 2868 1691 9229 2865 1692 9230 2867 1691 9231 2865 1701 9232 2868 1700 9233 2866 1702 9234 2871 1692 9235 2869 1693 9236 2870 1692 9237 2869 1702 9238 2871 1701 9239 2872 1703 9240 2875 1693 9241 2873 1694 9242 2874 1693 9243 2873 1703 9244 2875 1702 9245 2876 1704 9246 2878 1694 9247 2874 1695 9248 2877 1694 9249 2874 1704 9250 2878 1703 9251 2875 1696 9252 2879 1704 9253 2878 1695 9254 2877 1704 9255 2878 1696 9256 2879 1705 9257 2880 1706 9258 2883 1696 9259 2881 1697 9260 2882 1696 9261 2881 1706 9262 2883 1705 9263 2884 1698 9264 2886 1697 9265 2882 1689 9266 2885 1697 9267 2882 1698 9268 2886 1706 9269 2883 1698 9270 2887 1699 9271 2888 1707 9272 2889 1699 9273 2888 1700 9274 2890 1707 9275 2889 1700 9276 2890 1701 9277 2891 1707 9278 2889 1701 9279 2891 1702 9280 2892 1707 9281 2889 1702 9282 2892 1703 9283 2893 1707 9284 2889 1703 9285 2893 1704 9286 2894 1707 9287 2889 1704 9288 2894 1705 9289 2895 1707 9290 2889 1705 9291 2895 1706 9292 2896 1707 9293 2889 1706 9294 2896 1698 9295 2887 1707 9296 2889 1714 9297 2899 1709 9298 2900 1708 9299 2897 1714 9300 2899 1708 9301 2897 1713 9302 2898 1659 9303 2783 1714 9304 2899 1666 9305 2784 1714 9306 2899 1659 9307 2783 1709 9308 2900 1667 9309 2788 1715 9310 2901 1660 9311 2785 1660 9312 2785 1715 9313 2901 1710 9314 2902 1716 9315 2903 1710 9316 2902 1715 9317 2901 1710 9318 2902 1716 9319 2903 1711 9320 2904 1716 9321 2906 1717 9322 2907 1711 9323 2905 1711 9324 2905 1717 9325 2907 1712 9326 2908 1717 9327 2907 1713 9328 2909 1712 9329 2908 1712 9330 2908 1713 9331 2909 1708 9332 2910 1660 9333 2914 1755 9334 2912 1756 9335 2913 1755 9336 2912 1660 9337 2914 1710 9338 2911 1718 9339 2916 1714 9340 2918 1713 9341 2915 1714 9342 2918 1718 9343 2916 1719 9344 2917 1666 9345 2805 1714 9346 2918 1720 9347 2919 1720 9348 2919 1714 9349 2918 1719 9350 2917 1666 9351 2805 1720 9352 2919 1721 9353 2920 1666 9354 2805 1722 9355 2921 1667 9356 2808 1722 9357 2921 1666 9358 2805 1721 9359 2920 1667 9360 2808 1722 9361 2921 1723 9362 2922 1715 9363 2924 1667 9364 2808 1723 9365 2922 1723 9366 2922 1724 9367 2923 1715 9368 2924 1724 9369 2923 1725 9370 2925 1715 9371 2924 1716 9372 2926 1715 9373 2924 1725 9374 2925 1717 9375 2928 1716 9376 2926 1726 9377 2927 1726 9378 2927 1716 9379 2926 1725 9380 2925 1726 9381 2927 1713 9382 2915 1717 9383 2928 1713 9384 2915 1726 9385 2927 1718 9386 2916 1719 9387 2932 1718 9388 2929 1728 9389 2931 1728 9390 2931 1718 9391 2929 1727 9392 2930 1720 9393 2934 1728 9394 2931 1729 9395 2933 1728 9396 2931 1720 9397 2934 1719 9398 2932 1730 9399 2935 1720 9400 2934 1729 9401 2933 1720 9402 2934 1730 9403 2935 1721 9404 2936 1731 9405 2939 1721 9406 2937 1730 9407 2938 1721 9408 2937 1731 9409 2939 1722 9410 2940 1731 9411 2942 1732 9412 2943 1722 9413 2941 1722 9414 2941 1732 9415 2943 1723 9416 2944 1732 9417 2943 1733 9418 2945 1723 9419 2944 1723 9420 2944 1733 9421 2945 1724 9422 2946 1733 9423 2945 1734 9424 2947 1724 9425 2946 1724 9426 2946 1734 9427 2947 1725 9428 2948 1734 9429 2950 1735 9430 2951 1725 9431 2949 1725 9432 2949 1735 9433 2951 1726 9434 2952 1735 9435 2951 1727 9436 2953 1726 9437 2952 1726 9438 2952 1727 9439 2953 1718 9440 2954 1728 9441 2958 1727 9442 2955 1747 9443 2957 1727 9444 2955 1746 9445 2956 1747 9446 2957 1728 9447 2958 1754 9448 2959 1729 9449 2960 1754 9450 2959 1728 9451 2958 1747 9452 2957 1753 9453 2961 1729 9454 2960 1754 9455 2959 1729 9456 2960 1753 9457 2961 1730 9458 2962 1731 9459 2964 1753 9460 2961 1752 9461 2963 1753 9462 2961 1731 9463 2964 1730 9464 2962 1732 9465 2966 1752 9466 2963 1751 9467 2965 1752 9468 2963 1732 9469 2966 1731 9470 2964 1751 9471 2965 1733 9472 2968 1732 9473 2966 1733 9474 2968 1751 9475 2965 1750 9476 2967 1734 9477 2970 1750 9478 2967 1749 9479 2969 1750 9480 2967 1734 9481 2970 1733 9482 2968 1735 9483 2972 1749 9484 2969 1748 9485 2971 1749 9486 2969 1735 9487 2972 1734 9488 2970 1746 9489 2956 1735 9490 2972 1748 9491 2971 1735 9492 2972 1746 9493 2956 1727 9494 2955 1736 9495 2973 1745 9496 2974 1737 9497 2975 1737 9498 2975 1745 9499 2974 1738 9500 2976 1738 9501 2976 1745 9502 2974 1739 9503 2977 1739 9504 2977 1745 9505 2974 1740 9506 2978 1740 9507 2978 1745 9508 2974 1741 9509 2979 1741 9510 2979 1745 9511 2974 1742 9512 2980 1742 9513 2980 1745 9514 2974 1743 9515 2981 1743 9516 2981 1745 9517 2974 1744 9518 2982 1744 9519 2982 1745 9520 2974 1736 9521 2973 1747 9522 2986 1736 9523 2984 1737 9524 2985 1736 9525 2984 1747 9526 2986 1746 9527 2983 1738 9528 2987 1754 9529 2988 1747 9530 2986 1738 9531 2987 1747 9532 2986 1737 9533 2985 1754 9534 2988 1738 9535 2987 1739 9536 2989 1754 9537 2988 1739 9538 2989 1753 9539 2990 1753 9540 2991 1739 9541 2992 1740 9542 2993 1753 9543 2991 1740 9544 2993 1752 9545 2994 1752 9546 2995 1740 9547 2996 1741 9548 2997 1752 9549 2995 1741 9550 2997 1751 9551 2998 1751 9552 2998 1741 9553 2997 1742 9554 2999 1751 9555 2998 1742 9556 2999 1750 9557 3000 1750 9558 3000 1742 9559 2999 1743 9560 3001 1750 9561 3000 1743 9562 3001 1749 9563 3002 1749 9564 3003 1743 9565 3004 1744 9566 3005 1749 9567 3003 1744 9568 3005 1748 9569 3006 1748 9570 3006 1744 9571 3005 1736 9572 3007 1748 9573 3006 1736 9574 3007 1746 9575 3008 1757 9576 2799 1660 9577 2914 1756 9578 2913 1660 9579 2914 1757 9580 2799 1661 9581 2798 1755 9582 2912 1710 9583 2911 1711 9584 3009 1755 9585 2912 1711 9586 3009 1712 9587 3010 1709 9588 3012 1755 9589 2912 1708 9590 3011 1755 9591 2912 1712 9592 3010 1708 9593 3011 1755 9594 2912 1659 9595 3013 1756 9596 2913 1659 9597 3013 1755 9598 2912 1709 9599 3012 1757 9600 2799 1659 9601 3013 1658 9602 3014 1659 9603 3013 1757 9604 2799 1756 9605 2913 1757 9606 2799 1657 9607 3015 1663 9608 2800 1657 9609 3015 1757 9610 2799 1658 9611 3014 1765 9612 3017 1766 9613 3018 1758 9614 3016 1758 9615 3016 1766 9616 3018 1759 9617 3019 1766 9618 3018 1767 9619 3020 1759 9620 3019 1759 9621 3019 1767 9622 3020 1760 9623 3021 1762 9624 3025 1761 9625 3022 1769 9626 3024 1769 9627 3024 1761 9628 3022 1768 9629 3023 1770 9630 3026 1763 9631 3027 1762 9632 3025 1770 9633 3026 1762 9634 3025 1769 9635 3024 1771 9636 3030 1764 9637 3031 1763 9638 3028 1771 9639 3030 1763 9640 3028 1770 9641 3029 1758 9642 3033 1771 9643 3030 1765 9644 3032 1771 9645 3030 1758 9646 3033 1764 9647 3031 1764 9648 3035 1858 9649 3036 1763 9650 3034 1763 9651 3034 1858 9652 3036 1762 9653 3037 1766 9654 3041 1772 9655 3039 1773 9656 3040 1772 9657 3039 1766 9658 3041 1765 9659 3038 1774 9660 3042 1766 9661 3041 1773 9662 3040 1767 9663 3043 1766 9664 3041 1774 9665 3042 1767 9666 3043 1774 9667 3042 1775 9668 3044 1776 9669 3045 1767 9670 3043 1775 9671 3044 1768 9672 3046 1767 9673 3043 1776 9674 3045 1768 9675 3046 1776 9676 3045 1777 9677 3047 1769 9678 3049 1768 9679 3046 1777 9680 3047 1769 9681 3049 1777 9682 3047 1778 9683 3048 1769 9684 3049 1779 9685 3050 1770 9686 3051 1779 9687 3050 1769 9688 3049 1778 9689 3048 1780 9690 3052 1770 9691 3051 1779 9692 3050 1771 9693 3053 1770 9694 3051 1780 9695 3052 1765 9696 3038 1780 9697 3052 1772 9698 3039 1780 9699 3052 1765 9700 3038 1771 9701 3053 1781 9702 3055 1782 9703 3056 1772 9704 3054 1772 9705 3054 1782 9706 3056 1773 9707 3057 1782 9708 3056 1783 9709 3058 1773 9710 3057 1773 9711 3057 1783 9712 3058 1774 9713 3059 1775 9714 3061 1774 9715 3059 1784 9716 3060 1784 9717 3060 1774 9718 3059 1783 9719 3058 1776 9720 3065 1775 9721 3062 1785 9722 3064 1785 9723 3064 1775 9724 3062 1784 9725 3063 1777 9726 3069 1776 9727 3066 1786 9728 3068 1786 9729 3068 1776 9730 3066 1785 9731 3067 1778 9732 3071 1777 9733 3069 1787 9734 3070 1787 9735 3070 1777 9736 3069 1786 9737 3068 1779 9738 3073 1778 9739 3071 1788 9740 3072 1788 9741 3072 1778 9742 3071 1787 9743 3070 1780 9744 3077 1779 9745 3074 1789 9746 3076 1789 9747 3076 1779 9748 3074 1788 9749 3075 1772 9750 3079 1789 9751 3076 1781 9752 3078 1789 9753 3076 1772 9754 3079 1780 9755 3077 1781 9756 3080 1791 9757 3082 1782 9758 3083 1791 9759 3082 1781 9760 3080 1790 9761 3081 1792 9762 3084 1782 9763 3083 1791 9764 3082 1783 9765 3085 1782 9766 3083 1792 9767 3084 1784 9768 3087 1783 9769 3085 1793 9770 3086 1783 9771 3085 1792 9772 3084 1793 9773 3086 1785 9774 3089 1793 9775 3086 1794 9776 3088 1793 9777 3086 1785 9778 3089 1784 9779 3087 1794 9780 3088 1786 9781 3091 1785 9782 3089 1786 9783 3091 1794 9784 3088 1795 9785 3090 1787 9786 3093 1795 9787 3090 1796 9788 3092 1795 9789 3090 1787 9790 3093 1786 9791 3091 1788 9792 3095 1796 9793 3092 1797 9794 3094 1796 9795 3092 1788 9796 3095 1787 9797 3093 1797 9798 3094 1789 9799 3097 1788 9800 3095 1789 9801 3097 1797 9802 3094 1798 9803 3096 1781 9804 3080 1789 9805 3097 1790 9806 3081 1789 9807 3097 1798 9808 3096 1790 9809 3081 1790 9810 3098 1799 9811 3099 1800 9812 3100 1790 9813 3098 1800 9814 3100 1791 9815 3101 1801 9816 3102 1791 9817 3101 1800 9818 3100 1791 9819 3101 1801 9820 3102 1792 9821 3103 1802 9822 3104 1793 9823 3105 1792 9824 3103 1802 9825 3104 1792 9826 3103 1801 9827 3102 1803 9828 3108 1794 9829 3109 1793 9830 3106 1803 9831 3108 1793 9832 3106 1802 9833 3107 1804 9834 3112 1795 9835 3113 1794 9836 3110 1804 9837 3112 1794 9838 3110 1803 9839 3111 1805 9840 3114 1796 9841 3115 1795 9842 3113 1805 9843 3114 1795 9844 3113 1804 9845 3112 1806 9846 3116 1797 9847 3117 1796 9848 3115 1806 9849 3116 1796 9850 3115 1805 9851 3114 1798 9852 3121 1806 9853 3119 1807 9854 3120 1806 9855 3119 1798 9856 3121 1797 9857 3118 1799 9858 3122 1790 9859 3123 1798 9860 3121 1799 9861 3122 1798 9862 3121 1807 9863 3120 1799 9864 3124 1808 9865 3125 1800 9866 3126 1800 9867 3126 1808 9868 3125 1801 9869 3127 1801 9870 3127 1808 9871 3125 1802 9872 3128 1802 9873 3128 1808 9874 3125 1803 9875 3129 1803 9876 3129 1808 9877 3125 1804 9878 3130 1804 9879 3130 1808 9880 3125 1805 9881 3131 1805 9882 3131 1808 9883 3125 1806 9884 3132 1806 9885 3132 1808 9886 3125 1807 9887 3133 1807 9888 3133 1808 9889 3125 1799 9890 3124 1815 9891 3136 1809 9892 3134 1810 9893 3135 1809 9894 3134 1815 9895 3136 1814 9896 3137 1767 9897 3020 1810 9898 3135 1760 9899 3021 1810 9900 3135 1767 9901 3020 1815 9902 3136 1816 9903 3139 1768 9904 3023 1761 9905 3022 1761 9906 3022 1811 9907 3138 1816 9908 3139 1816 9909 3139 1811 9910 3138 1817 9911 3141 1811 9912 3138 1812 9913 3140 1817 9914 3141 1817 9915 3145 1813 9916 3143 1818 9917 3144 1813 9918 3143 1817 9919 3145 1812 9920 3142 1818 9921 3144 1813 9922 3143 1814 9923 3147 1813 9924 3143 1809 9925 3146 1814 9926 3147 1856 9927 3151 1761 9928 3149 1857 9929 3150 1761 9930 3149 1856 9931 3151 1811 9932 3148 1815 9933 3153 1819 9934 3155 1814 9935 3152 1819 9936 3155 1815 9937 3153 1820 9938 3154 1815 9939 3153 1767 9940 3043 1821 9941 3156 1815 9942 3153 1821 9943 3156 1820 9944 3154 1767 9945 3043 1822 9946 3157 1821 9947 3156 1823 9948 3158 1767 9949 3043 1768 9950 3046 1767 9951 3043 1823 9952 3158 1822 9953 3157 1768 9954 3046 1824 9955 3159 1823 9956 3158 1816 9957 3160 1824 9958 3159 1768 9959 3046 1824 9960 3159 1816 9961 3160 1825 9962 3161 1826 9963 3163 1816 9964 3160 1817 9965 3162 1816 9966 3160 1826 9967 3163 1825 9968 3161 1817 9969 3162 1827 9970 3165 1826 9971 3163 1827 9972 3165 1817 9973 3162 1818 9974 3164 1827 9975 3165 1814 9976 3152 1819 9977 3155 1814 9978 3152 1827 9979 3165 1818 9980 3164 1829 9981 3168 1819 9982 3166 1820 9983 3167 1819 9984 3166 1829 9985 3168 1828 9986 3169 1830 9987 3171 1820 9988 3167 1821 9989 3170 1820 9990 3167 1830 9991 3171 1829 9992 3168 1831 9993 3173 1830 9994 3171 1821 9995 3170 1821 9996 3170 1822 9997 3172 1831 9998 3173 1832 9999 3176 1831 10000 3177 1822 10001 3174 1822 10002 3174 1823 10003 3175 1832 10004 3176 1833 10005 3180 1832 10006 3181 1823 10007 3178 1823 10008 3178 1824 10009 3179 1833 10010 3180 1834 10011 3183 1833 10012 3180 1824 10013 3179 1824 10014 3179 1825 10015 3182 1834 10016 3183 1835 10017 3185 1834 10018 3183 1825 10019 3182 1825 10020 3182 1826 10021 3184 1835 10022 3185 1835 10023 3189 1827 10024 3187 1836 10025 3188 1827 10026 3187 1835 10027 3189 1826 10028 3186 1828 10029 3191 1836 10030 3188 1827 10031 3187 1827 10032 3187 1819 10033 3190 1828 10034 3191 1829 10035 3193 1848 10036 3194 1828 10037 3192 1828 10038 3192 1848 10039 3194 1847 10040 3195 1829 10041 3193 1855 10042 3197 1848 10043 3194 1855 10044 3197 1829 10045 3193 1830 10046 3196 1854 10047 3199 1855 10048 3197 1830 10049 3196 1830 10050 3196 1831 10051 3198 1854 10052 3199 1832 10053 3200 1854 10054 3199 1831 10055 3198 1854 10056 3199 1832 10057 3200 1853 10058 3201 1853 10059 3201 1833 10060 3202 1852 10061 3203 1833 10062 3202 1853 10063 3201 1832 10064 3200 1852 10065 3203 1834 10066 3204 1851 10067 3205 1834 10068 3204 1852 10069 3203 1833 10070 3202 1835 10071 3206 1851 10072 3205 1834 10073 3204 1851 10074 3205 1835 10075 3206 1850 10076 3207 1850 10077 3207 1836 10078 3208 1849 10079 3209 1836 10080 3208 1850 10081 3207 1835 10082 3206 1847 10083 3195 1849 10084 3209 1836 10085 3208 1836 10086 3208 1828 10087 3192 1847 10088 3195 1837 10089 3210 1838 10090 3211 1846 10091 3212 1838 10092 3211 1839 10093 3213 1846 10094 3212 1839 10095 3213 1840 10096 3214 1846 10097 3212 1840 10098 3214 1841 10099 3215 1846 10100 3212 1841 10101 3215 1842 10102 3216 1846 10103 3212 1842 10104 3216 1843 10105 3217 1846 10106 3212 1843 10107 3217 1844 10108 3218 1846 10109 3212 1844 10110 3218 1845 10111 3219 1846 10112 3212 1845 10113 3219 1837 10114 3210 1846 10115 3212 1838 10116 3222 1847 10117 3220 1848 10118 3221 1847 10119 3220 1838 10120 3222 1837 10121 3223 1839 10122 3225 1848 10123 3221 1855 10124 3224 1848 10125 3221 1839 10126 3225 1838 10127 3222 1854 10128 3226 1840 10129 3227 1855 10130 3224 1839 10131 3225 1855 10132 3224 1840 10133 3227 1853 10134 3229 1841 10135 3230 1854 10136 3228 1840 10137 3231 1854 10138 3228 1841 10139 3230 1852 10140 3233 1842 10141 3234 1853 10142 3232 1841 10143 3235 1853 10144 3232 1842 10145 3234 1851 10146 3236 1843 10147 3237 1852 10148 3233 1842 10149 3234 1852 10150 3233 1843 10151 3237 1850 10152 3238 1844 10153 3239 1851 10154 3236 1843 10155 3237 1851 10156 3236 1844 10157 3239 1849 10158 3241 1845 10159 3242 1850 10160 3240 1844 10161 3243 1850 10162 3240 1845 10163 3242 1847 10164 3244 1845 10165 3242 1849 10166 3241 1845 10167 3242 1847 10168 3244 1837 10169 3245 1858 10170 3036 1761 10171 3149 1762 10172 3037 1761 10173 3149 1858 10174 3036 1857 10175 3150 1811 10176 3148 1856 10177 3151 1812 10178 3246 1812 10179 3246 1856 10180 3151 1813 10181 3247 1810 10182 3248 1809 10183 3249 1856 10184 3151 1856 10185 3151 1809 10186 3249 1813 10187 3247 1760 10188 3250 1856 10189 3151 1857 10190 3150 1856 10191 3151 1760 10192 3250 1810 10193 3248 1858 10194 3036 1760 10195 3250 1857 10196 3150 1760 10197 3250 1858 10198 3036 1759 10199 3251 1758 10200 3252 1858 10201 3036 1764 10202 3035 1858 10203 3036 1758 10204 3252 1759 10205 3251 1869 10206 3255 1859 10207 3253 1860 10208 3254 1859 10209 3253 1869 10210 3255 1868 10211 3256 1870 10212 3258 1860 10213 3254 1861 10214 3257 1860 10215 3254 1870 10216 3258 1869 10217 3255 1862 10218 3259 1871 10219 3260 1861 10220 3257 1870 10221 3258 1861 10222 3257 1871 10223 3260 1863 10224 3261 1872 10225 3262 1862 10226 3259 1871 10227 3260 1862 10228 3259 1872 10229 3262 1864 10230 3263 1873 10231 3264 1863 10232 3261 1872 10233 3262 1863 10234 3261 1873 10235 3264 1865 10236 3265 1874 10237 3266 1864 10238 3263 1873 10239 3264 1864 10240 3263 1874 10241 3266 1866 10242 3267 1875 10243 3268 1865 10244 3265 1874 10245 3266 1865 10246 3265 1875 10247 3268 1867 10248 3269 1876 10249 3270 1866 10250 3267 1875 10251 3268 1866 10252 3267 1876 10253 3270 1859 10254 3271 1876 10255 3270 1867 10256 3269 1876 10257 3270 1859 10258 3271 1868 10259 3272 1883 10260 3276 1877 10261 3274 1882 10262 3275 1877 10263 3274 1883 10264 3276 1878 10265 3273 1881 10266 3277 1880 10267 3278 1885 10268 3279 1881 10269 3277 1885 10270 3279 1884 10271 3280 1885 10272 3279 1880 10273 3278 1898 10274 3282 1880 10275 3278 1897 10276 3281 1898 10277 3282 1878 10278 3273 1886 10279 3284 1879 10280 3283 1886 10281 3284 1878 10282 3273 1883 10283 3276 1882 10284 3286 1892 10285 3287 1883 10286 3285 1893 10287 3288 1883 10288 3285 1892 10289 3287 1883 10290 3285 1893 10291 3288 1886 10292 3289 1896 10293 3290 1886 10294 3289 1893 10295 3288 1887 10296 3293 1877 10297 3294 1878 10298 3291 1887 10299 3293 1878 10300 3291 1888 10301 3292 1888 10302 3292 1879 10303 3295 1889 10304 3296 1879 10305 3295 1888 10306 3292 1878 10307 3291 1880 10308 3297 1890 10309 3298 1900 10310 3299 1880 10311 3297 1900 10312 3299 1897 10313 3300 1880 10314 3297 1891 10315 3302 1890 10316 3298 1891 10317 3302 1880 10318 3297 1881 10319 3301 1887 10320 3306 1893 10321 3304 1892 10322 3305 1893 10323 3304 1887 10324 3306 1888 10325 3303 1891 10326 3307 1895 10327 3309 1890 10328 3310 1895 10329 3309 1891 10330 3307 1894 10331 3308 1899 10332 3311 1890 10333 3310 1895 10334 3309 1890 10335 3310 1899 10336 3311 1900 10337 3312 1896 10338 3314 1888 10339 3303 1889 10340 3313 1888 10341 3303 1896 10342 3314 1893 10343 3304 1894 10344 3317 1884 10345 3318 1885 10346 3315 1894 10347 3317 1885 10348 3315 1895 10349 3316 1895 10350 3316 1885 10351 3315 1898 10352 3319 1895 10353 3316 1898 10354 3319 1899 10355 3320 1886 10356 3284 1898 10357 3282 1897 10358 3281 1897 10359 3281 1879 10360 3283 1886 10361 3284 1899 10362 3320 1898 10363 3319 1886 10364 3289 1899 10365 3320 1886 10366 3289 1896 10367 3290 1899 10368 3311 1896 10369 3314 1900 10370 3312 1900 10371 3312 1896 10372 3314 1889 10373 3313 1897 10374 3300 1900 10375 3299 1879 10376 3295 1900 10377 3299 1889 10378 3296 1879 10379 3295 1884 10380 3280 1901 10381 3321 1881 10382 3277 1901 10383 3321 1884 10384 3280 1902 10385 3322 1903 10386 3323 1902 10387 3324 1884 10388 3318 1903 10389 3323 1884 10390 3318 1894 10391 3317 1891 10392 3307 1904 10393 3325 1894 10394 3308 1904 10395 3325 1903 10396 3326 1894 10397 3308 1891 10398 3302 1881 10399 3301 1901 10400 3327 1891 10401 3302 1901 10402 3327 1904 10403 3328 1877 10404 3274 1909 10405 3330 1882 10406 3275 1909 10407 3330 1877 10408 3274 1905 10409 3329 1908 10410 3331 1911 10411 3333 1907 10412 3334 1911 10413 3333 1908 10414 3331 1910 10415 3332 1922 10416 3335 1907 10417 3334 1911 10418 3333 1907 10419 3334 1922 10420 3335 1921 10421 3336 1912 10422 3338 1905 10423 3329 1906 10424 3337 1905 10425 3329 1912 10426 3338 1909 10427 3330 1918 10428 3341 1911 10429 3339 1910 10430 3340 1911 10431 3339 1918 10432 3341 1919 10433 3342 1919 10434 3342 1922 10435 3343 1911 10436 3339 1922 10437 3343 1919 10438 3342 1923 10439 3344 1913 10440 3348 1877 10441 3346 1887 10442 3347 1877 10443 3346 1913 10444 3348 1905 10445 3345 1914 10446 3350 1906 10447 3349 1913 10448 3348 1906 10449 3349 1905 10450 3345 1913 10451 3348 1921 10452 3352 1924 10453 3353 1907 10454 3351 1915 10455 3354 1907 10456 3351 1924 10457 3353 1907 10458 3351 1915 10459 3354 1908 10460 3355 1916 10461 3356 1908 10462 3355 1915 10463 3354 1917 10464 3358 1887 10465 3306 1892 10466 3305 1887 10467 3306 1917 10468 3358 1913 10469 3357 1916 10470 3359 1915 10471 3360 1919 10472 3361 1916 10473 3359 1919 10474 3361 1918 10475 3362 1919 10476 3361 1915 10477 3360 1923 10478 3364 1915 10479 3360 1924 10480 3363 1923 10481 3364 1913 10482 3357 1920 10483 3366 1914 10484 3365 1920 10485 3366 1913 10486 3357 1917 10487 3358 1882 10488 3370 1917 10489 3368 1892 10490 3369 1917 10491 3368 1882 10492 3370 1909 10493 3367 1917 10494 3368 1909 10495 3367 1920 10496 3371 1912 10497 3372 1920 10498 3371 1909 10499 3367 1922 10500 3335 1912 10501 3338 1921 10502 3336 1921 10503 3336 1912 10504 3338 1906 10505 3337 1923 10506 3344 1912 10507 3372 1922 10508 3343 1912 10509 3372 1923 10510 3344 1920 10511 3371 1920 10512 3366 1923 10513 3364 1924 10514 3363 1924 10515 3363 1914 10516 3365 1920 10517 3366 1921 10518 3352 1906 10519 3349 1924 10520 3353 1924 10521 3353 1906 10522 3349 1914 10523 3350 1908 10524 3331 1901 10525 3321 1910 10526 3332 1901 10527 3321 1902 10528 3322 1910 10529 3332 1902 10530 3324 1918 10531 3341 1910 10532 3340 1918 10533 3341 1902 10534 3324 1903 10535 3323 1918 10536 3362 1904 10537 3325 1916 10538 3359 1904 10539 3325 1918 10540 3362 1903 10541 3326 1908 10542 3355 1916 10543 3356 1901 10544 3327 1904 10545 3328 1901 10546 3327 1916 10547 3356 1932 10548 3375 1935 10549 3373 1928 10550 3374 1935 10551 3373 1932 10552 3375 1937 10553 3376 1940 10554 3378 1931 10555 3380 1929 10556 3377 1931 10557 3380 1940 10558 3378 1939 10559 3379 1930 10560 3382 1928 10561 3374 1927 10562 3381 1928 10563 3374 1930 10564 3382 1932 10565 3375 1931 10566 3380 1927 10567 3383 1929 10568 3377 1927 10569 3383 1931 10570 3380 1930 10571 3384 1933 10572 3386 1936 10573 3387 1934 10574 3385 1938 10575 3388 1934 10576 3385 1936 10577 3387 1937 10578 3376 1933 10579 3389 1935 10580 3373 1933 10581 3389 1937 10582 3376 1936 10583 3390 1925 10584 3392 1938 10585 3388 1926 10586 3391 1938 10587 3388 1925 10588 3392 1934 10589 3385 1929 10590 3394 1928 10591 3396 1934 10592 3393 1928 10593 3396 1929 10594 3394 1927 10595 3395 1938 10596 3398 1932 10597 3399 1931 10598 3397 1931 10599 3397 1932 10600 3399 1930 10601 3400 1926 10602 3402 1938 10603 3398 1939 10604 3401 1939 10605 3401 1938 10606 3398 1931 10607 3397 1940 10608 3404 1934 10609 3393 1925 10610 3403 1934 10611 3393 1940 10612 3404 1929 10613 3394 1934 10614 3393 1928 10615 3396 1935 10616 3405 1934 10617 3393 1935 10618 3405 1933 10619 3406 1938 10620 3398 1937 10621 3408 1932 10622 3399 1937 10623 3408 1938 10624 3398 1936 10625 3407 1941 10626 3411 1942 10627 3412 1939 10628 3409 1941 10629 3411 1939 10630 3409 1940 10631 3410 1925 10632 3403 1943 10633 3413 1940 10634 3404 1940 10635 3404 1943 10636 3413 1941 10637 3414 1926 10638 3416 1943 10639 3418 1925 10640 3415 1943 10641 3418 1926 10642 3416 1944 10643 3417 1939 10644 3401 1944 10645 3420 1926 10646 3402 1944 10647 3420 1939 10648 3401 1942 10649 3419 1971 10650 3422 1973 10651 3424 1970 10652 3421 1973 10653 3424 1971 10654 3422 1972 10655 3423 1974 10656 3425 1972 10657 3423 1971 10658 3422 1972 10659 3423 1974 10660 3425 1975 10661 3426 1977 10662 3428 1974 10663 3425 1976 10664 3427 1974 10665 3425 1977 10666 3428 1975 10667 3426 1979 10668 3430 1976 10669 3427 1978 10670 3429 1976 10671 3427 1979 10672 3430 1977 10673 3428 1981 10674 3432 1979 10675 3430 1978 10676 3429 1981 10677 3432 1978 10678 3429 1980 10679 3431 1981 10680 3436 1982 10681 3434 1983 10682 3435 1982 10683 3434 1981 10684 3436 1980 10685 3433 1983 10686 3435 1984 10687 3437 1985 10688 3438 1984 10689 3437 1983 10690 3435 1982 10691 3434 1985 10692 3438 1986 10693 3439 1987 10694 3440 1986 10695 3439 1985 10696 3438 1984 10697 3437 1987 10698 3440 1986 10699 3439 1989 10700 3442 1986 10701 3439 1988 10702 3441 1989 10703 3442 1989 10704 3442 1988 10705 3441 1991 10706 3444 1988 10707 3441 1990 10708 3443 1991 10709 3444 1991 10710 3444 1992 10711 3445 1993 10712 3446 1992 10713 3445 1991 10714 3444 1990 10715 3443 1973 10716 3424 1993 10717 3446 1992 10718 3445 1973 10719 3424 1992 10720 3445 1970 10721 3421 1970 10722 3450 1958 10723 3448 1971 10724 3449 1958 10725 3448 1970 10726 3450 1957 10727 3447 1969 10728 3451 1973 10729 3452 1972 10730 3453 1971 10731 3449 1959 10732 3454 1974 10733 3455 1959 10734 3454 1971 10735 3449 1958 10736 3448 1969 10737 3451 1972 10738 3453 1975 10739 3456 1976 10740 3458 1959 10741 3454 1960 10742 3457 1959 10743 3454 1976 10744 3458 1974 10745 3455 1969 10746 3451 1975 10747 3456 1977 10748 3459 1960 10749 3457 1961 10750 3460 1978 10751 3461 1960 10752 3457 1978 10753 3461 1976 10754 3458 1969 10755 3451 1977 10756 3459 1979 10757 3462 1980 10758 3464 1978 10759 3461 1961 10760 3460 1980 10761 3464 1961 10762 3460 1962 10763 3463 1969 10764 3451 1979 10765 3462 1981 10766 3465 1980 10767 3464 1963 10768 3466 1982 10769 3467 1963 10770 3466 1980 10771 3464 1962 10772 3463 1969 10773 3451 1981 10774 3465 1983 10775 3468 1964 10776 3469 1982 10777 3467 1963 10778 3466 1982 10779 3467 1964 10780 3469 1984 10781 3470 1969 10782 3451 1983 10783 3468 1985 10784 3471 1965 10785 3472 1984 10786 3470 1964 10787 3469 1984 10788 3470 1965 10789 3472 1986 10790 3473 1969 10791 3451 1985 10792 3471 1987 10793 3474 1988 10794 3476 1986 10795 3473 1965 10796 3472 1988 10797 3476 1965 10798 3472 1966 10799 3475 1969 10800 3451 1987 10801 3474 1989 10802 3477 1990 10803 3479 1988 10804 3476 1966 10805 3475 1990 10806 3479 1966 10807 3475 1967 10808 3478 1969 10809 3451 1989 10810 3477 1991 10811 3480 1992 10812 3482 1967 10813 3478 1968 10814 3481 1967 10815 3478 1992 10816 3482 1990 10817 3479 1969 10818 3451 1991 10819 3480 1993 10820 3483 1957 10821 3447 1992 10822 3482 1968 10823 3481 1992 10824 3482 1957 10825 3447 1970 10826 3450 1969 10827 3451 1993 10828 3483 1973 10829 3452 1995 10830 3485 2016 10831 3487 1994 10832 3484 2016 10833 3487 1995 10834 3485 2017 10835 3486 1996 10836 3488 1997 10837 3489 1995 10838 3485 1995 10839 3485 1994 10840 3484 1996 10841 3488 1999 10842 3491 1997 10843 3489 1998 10844 3490 1997 10845 3489 1996 10846 3488 1998 10847 3490 2001 10848 3493 1999 10849 3491 2000 10850 3492 1999 10851 3491 1998 10852 3490 2000 10853 3492 2002 10854 3494 2003 10855 3495 2001 10856 3493 2001 10857 3493 2000 10858 3492 2002 10859 3494 2005 10860 3497 2003 10861 3495 2004 10862 3496 2003 10863 3495 2002 10864 3494 2004 10865 3496 2007 10866 3501 2005 10867 3498 2006 10868 3500 2005 10869 3498 2004 10870 3499 2006 10871 3500 2006 10872 3500 2009 10873 3503 2007 10874 3501 2009 10875 3503 2006 10876 3500 2008 10877 3502 2008 10878 3502 2011 10879 3505 2009 10880 3503 2011 10881 3505 2008 10882 3502 2010 10883 3504 2010 10884 3504 2013 10885 3507 2011 10886 3505 2013 10887 3507 2010 10888 3504 2012 10889 3506 2012 10890 3506 2015 10891 3509 2013 10892 3507 2015 10893 3509 2012 10894 3506 2014 10895 3508 2017 10896 3486 2015 10897 3509 2016 10898 3487 2015 10899 3509 2014 10900 3508 2016 10901 3487 1994 10902 3484 1945 10903 3510 1996 10904 3488 1996 10905 3488 1945 10906 3510 1946 10907 3511 1998 10908 3490 1996 10909 3488 1946 10910 3511 1998 10911 3490 1946 10912 3511 1947 10913 3512 1998 10914 3490 1948 10915 3513 2000 10916 3492 1948 10917 3513 1998 10918 3490 1947 10919 3512 2000 10920 3492 1949 10921 3514 2002 10922 3494 1949 10923 3514 2000 10924 3492 1948 10925 3513 2002 10926 3494 1950 10927 3515 2004 10928 3496 1950 10929 3515 2002 10930 3494 1949 10931 3514 2006 10932 3500 2004 10933 3499 1950 10934 3516 2006 10935 3500 1950 10936 3516 1951 10937 3517 2006 10938 3500 1951 10939 3517 2008 10940 3502 2008 10941 3502 1951 10942 3517 1952 10943 3518 2010 10944 3504 2008 10945 3502 1952 10946 3518 2010 10947 3504 1952 10948 3518 1953 10949 3519 2010 10950 3504 1954 10951 3520 2012 10952 3506 1954 10953 3520 2010 10954 3504 1953 10955 3519 2012 10956 3506 1955 10957 3521 2014 10958 3508 1955 10959 3521 2012 10960 3506 1954 10961 3520 2014 10962 3508 1956 10963 3522 2016 10964 3487 1956 10965 3522 2014 10966 3508 1955 10967 3521 1994 10968 3484 2016 10969 3487 1956 10970 3522 1994 10971 3484 1956 10972 3522 1945 10973 3510 1957 10974 3524 1997 10975 3489 1958 10976 3523 1997 10977 3489 1957 10978 3524 1995 10979 3485 1958 10980 3523 1999 10981 3491 1959 10982 3525 1999 10983 3491 1958 10984 3523 1997 10985 3489 1959 10986 3525 2001 10987 3493 1960 10988 3526 2001 10989 3493 1959 10990 3525 1999 10991 3491 1960 10992 3526 2003 10993 3495 1961 10994 3527 2003 10995 3495 1960 10996 3526 2001 10997 3493 1961 10998 3527 2003 10999 3495 1962 11000 3528 1962 11001 3528 2003 11002 3495 2005 11003 3497 1962 11004 3530 2007 11005 3501 1963 11006 3529 2007 11007 3501 1962 11008 3530 2005 11009 3498 2009 11010 3503 1964 11011 3531 2007 11012 3501 1963 11013 3529 2007 11014 3501 1964 11015 3531 2011 11016 3505 1965 11017 3532 2009 11018 3503 1964 11019 3531 2009 11020 3503 1965 11021 3532 2013 11022 3507 1966 11023 3533 2011 11024 3505 1965 11025 3532 2011 11026 3505 1966 11027 3533 2015 11028 3509 1967 11029 3534 2013 11030 3507 1966 11031 3533 2013 11032 3507 1967 11033 3534 1967 11034 3534 2017 11035 3486 1968 11036 3535 2017 11037 3486 1967 11038 3534 2015 11039 3509 1968 11040 3535 2017 11041 3486 1957 11042 3524 1957 11043 3524 2017 11044 3486 1995 11045 3485 2026 11046 3537 2018 11047 3539 2028 11048 3536 2018 11049 3539 2026 11050 3537 2025 11051 3538 2028 11052 3536 2029 11053 3541 2027 11054 3540 2028 11055 3536 2027 11056 3540 2026 11057 3537 2028 11058 3536 2018 11059 3539 2019 11060 3542 2019 11061 3542 2030 11062 3543 2028 11063 3536 2030 11064 3543 2031 11065 3544 2029 11066 3541 2030 11067 3543 2029 11068 3541 2028 11069 3536 2032 11070 3545 2019 11071 3542 2020 11072 3546 2019 11073 3542 2032 11074 3545 2030 11075 3543 2032 11076 3545 2033 11077 3547 2031 11078 3544 2032 11079 3545 2031 11080 3544 2030 11081 3543 2032 11082 3545 2021 11083 3549 2034 11084 3548 2021 11085 3549 2032 11086 3545 2020 11087 3546 2034 11088 3548 2035 11089 3550 2033 11090 3547 2034 11091 3548 2033 11092 3547 2032 11093 3545 2034 11094 3548 2021 11095 3549 2036 11096 3551 2022 11097 3552 2036 11098 3551 2021 11099 3549 2037 11100 3553 2034 11101 3548 2036 11102 3551 2034 11103 3548 2037 11104 3553 2035 11105 3550 2036 11106 3551 2023 11107 3555 2038 11108 3554 2023 11109 3555 2036 11110 3551 2022 11111 3552 2036 11112 3551 2039 11113 3556 2037 11114 3553 2039 11115 3556 2036 11116 3551 2038 11117 3554 2038 11118 3554 2023 11119 3555 2040 11120 3557 2024 11121 3558 2040 11122 3557 2023 11123 3555 2038 11124 3554 2041 11125 3559 2039 11126 3556 2041 11127 3559 2038 11128 3554 2040 11129 3557 2040 11130 3557 2024 11131 3558 2026 11132 3560 2025 11133 3561 2026 11134 3560 2024 11135 3558 2027 11136 3562 2040 11137 3557 2026 11138 3560 2040 11139 3557 2027 11140 3562 2041 11141 3559 2043 11142 3564 2031 11143 3544 2044 11144 3563 2031 11145 3544 2043 11146 3564 2029 11147 3541 2044 11148 3563 2033 11149 3547 2045 11150 3565 2033 11151 3547 2044 11152 3563 2031 11153 3544 2045 11154 3565 2033 11155 3547 2046 11156 3566 2046 11157 3566 2033 11158 3547 2035 11159 3550 2046 11160 3566 2037 11161 3553 2047 11162 3567 2037 11163 3553 2046 11164 3566 2035 11165 3550 2039 11166 3556 2048 11167 3568 2037 11168 3553 2047 11169 3567 2037 11170 3553 2048 11171 3568 2041 11172 3559 2049 11173 3569 2039 11174 3556 2048 11175 3568 2039 11176 3556 2049 11177 3569 2049 11178 3569 2027 11179 3562 2042 11180 3570 2027 11181 3562 2049 11182 3569 2041 11183 3559 2042 11184 3571 2027 11185 3540 2043 11186 3564 2043 11187 3564 2027 11188 3540 2029 11189 3541 2042 11190 3572 2043 11191 3573 2050 11192 3574 2043 11193 3575 2044 11194 3576 2050 11195 3577 2051 11196 3579 2050 11197 3577 2044 11198 3576 2051 11199 3579 2044 11200 3576 2045 11201 3578 2045 11202 3580 2046 11203 3581 2051 11204 3582 2046 11205 3581 2047 11206 3583 2052 11207 3584 2052 11208 3588 2048 11209 3586 2053 11210 3587 2048 11211 3586 2052 11212 3588 2047 11213 3585 2048 11214 3586 2049 11215 3589 2053 11216 3587 2049 11217 3590 2042 11218 3572 2053 11219 3591 2058 11220 3593 2051 11221 3579 2061 11222 3592 2051 11223 3579 2058 11224 3593 2050 11225 3577 2067 11226 3594 2064 11227 3595 2052 11228 3588 2067 11229 3594 2052 11230 3588 2053 11231 3587 2054 11232 3599 2055 11233 3596 2065 11234 3598 2055 11235 3596 2063 11236 3597 2065 11237 3598 2059 11238 3601 2054 11239 3599 2057 11240 3600 2054 11241 3599 2059 11242 3601 2055 11243 3596 2056 11244 3602 2059 11245 3601 2057 11246 3600 2059 11247 3601 2056 11248 3602 2060 11249 3603 2060 11250 3603 2056 11251 3602 2061 11252 3592 2056 11253 3602 2058 11254 3593 2061 11255 3592 2062 11256 3604 2066 11257 3605 2063 11258 3597 2065 11259 3598 2063 11260 3597 2066 11261 3605 2066 11262 3605 2064 11263 3595 2067 11264 3594 2064 11265 3595 2066 11266 3605 2062 11267 3604 2054 11268 3608 2050 11269 3574 2058 11270 3609 2057 11271 3607 2058 11272 3609 2056 11273 3606 2054 11274 3608 2058 11275 3609 2057 11276 3607 2050 11277 3574 2054 11278 3608 2042 11279 3572 2046 11280 3581 2055 11281 3610 2061 11282 3613 2046 11283 3581 2061 11284 3613 2051 11285 3582 2061 11286 3613 2055 11287 3610 2059 11288 3611 2061 11289 3613 2059 11290 3611 2060 11291 3612 2055 11292 3610 2046 11293 3581 2064 11294 3616 2063 11295 3615 2064 11296 3616 2062 11297 3614 2055 11298 3610 2064 11299 3616 2063 11300 3615 2064 11301 3616 2046 11302 3581 2052 11303 3584 2054 11304 3608 2053 11305 3591 2042 11306 3572 2053 11307 3591 2054 11308 3608 2067 11309 3619 2067 11310 3619 2054 11311 3608 2065 11312 3617 2067 11313 3619 2065 11314 3617 2066 11315 3618 2018 11316 3539 2068 11317 3621 2070 11318 3620 2068 11319 3621 2018 11320 3539 2025 11321 3538 2071 11322 3623 2070 11323 3620 2069 11324 3622 2069 11325 3622 2070 11326 3620 2068 11327 3621 2070 11328 3620 2019 11329 3542 2018 11330 3539 2019 11331 3542 2070 11332 3620 2072 11333 3624 2072 11334 3624 2071 11335 3623 2073 11336 3625 2070 11337 3620 2071 11338 3623 2072 11339 3624 2074 11340 3626 2019 11341 3542 2072 11342 3624 2019 11343 3542 2074 11344 3626 2020 11345 3546 2074 11346 3626 2073 11347 3625 2075 11348 3627 2072 11349 3624 2073 11350 3625 2074 11351 3626 2021 11352 3549 2074 11353 3626 2076 11354 3628 2074 11355 3626 2021 11356 3549 2020 11357 3546 2077 11358 3629 2076 11359 3628 2075 11360 3627 2075 11361 3627 2076 11362 3628 2074 11363 3626 2078 11364 3630 2022 11365 3552 2021 11366 3549 2078 11367 3630 2021 11368 3549 2076 11369 3628 2076 11370 3628 2079 11371 3631 2078 11372 3630 2079 11373 3631 2076 11374 3628 2077 11375 3629 2023 11376 3555 2078 11377 3630 2080 11378 3632 2078 11379 3630 2023 11380 3555 2022 11381 3552 2078 11382 3630 2081 11383 3633 2080 11384 3632 2081 11385 3633 2078 11386 3630 2079 11387 3631 2023 11388 3555 2082 11389 3634 2024 11390 3558 2082 11391 3634 2023 11392 3555 2080 11393 3632 2080 11394 3632 2083 11395 3635 2082 11396 3634 2083 11397 3635 2080 11398 3632 2081 11399 3633 2068 11400 3636 2025 11401 3561 2024 11402 3558 2068 11403 3636 2024 11404 3558 2082 11405 3634 2082 11406 3634 2069 11407 3637 2068 11408 3636 2069 11409 3637 2082 11410 3634 2083 11411 3635 2073 11412 3625 2085 11413 3638 2086 11414 3639 2085 11415 3638 2073 11416 3625 2071 11417 3623 2075 11418 3627 2086 11419 3639 2087 11420 3640 2086 11421 3639 2075 11422 3627 2073 11423 3625 2088 11424 3641 2075 11425 3627 2087 11426 3640 2075 11427 3627 2088 11428 3641 2077 11429 3629 2088 11430 3641 2079 11431 3631 2077 11432 3629 2079 11433 3631 2088 11434 3641 2089 11435 3642 2090 11436 3643 2079 11437 3631 2089 11438 3642 2079 11439 3631 2090 11440 3643 2081 11441 3633 2091 11442 3644 2081 11443 3633 2090 11444 3643 2081 11445 3633 2091 11446 3644 2083 11447 3635 2091 11448 3644 2069 11449 3637 2083 11450 3635 2069 11451 3637 2091 11452 3644 2084 11453 3645 2085 11454 3638 2069 11455 3622 2084 11456 3646 2069 11457 3622 2085 11458 3638 2071 11459 3623 2084 11460 3647 2092 11461 3648 2085 11462 3649 2085 11463 3650 2092 11464 3651 2086 11465 3652 2093 11466 3653 2086 11467 3652 2092 11468 3651 2086 11469 3652 2093 11470 3653 2087 11471 3654 2087 11472 3655 2093 11473 3656 2088 11474 3657 2088 11475 3657 2094 11476 3658 2089 11477 3659 2094 11478 3661 2090 11479 3663 2089 11480 3660 2090 11481 3663 2094 11482 3661 2095 11483 3662 2090 11484 3663 2095 11485 3662 2091 11486 3664 2091 11487 3665 2095 11488 3666 2084 11489 3647 2100 11490 3667 2093 11491 3653 2092 11492 3651 2093 11493 3653 2100 11494 3667 2103 11495 3668 2109 11496 3670 2094 11497 3661 2106 11498 3669 2094 11499 3661 2109 11500 3670 2095 11501 3662 2096 11502 3672 2107 11503 3673 2097 11504 3671 2097 11505 3671 2107 11506 3673 2105 11507 3674 2101 11508 3675 2099 11509 3676 2096 11510 3672 2101 11511 3675 2096 11512 3672 2097 11513 3671 2098 11514 3678 2101 11515 3675 2102 11516 3677 2101 11517 3675 2098 11518 3678 2099 11519 3676 2102 11520 3677 2103 11521 3668 2098 11522 3678 2098 11523 3678 2103 11524 3668 2100 11525 3667 2108 11526 3679 2105 11527 3674 2107 11528 3673 2105 11529 3674 2108 11530 3679 2104 11531 3680 2108 11532 3679 2106 11533 3669 2104 11534 3680 2106 11535 3669 2108 11536 3679 2109 11537 3670 2096 11538 3683 2092 11539 3648 2084 11540 3647 2100 11541 3682 2099 11542 3684 2098 11543 3681 2100 11544 3682 2096 11545 3683 2099 11546 3684 2092 11547 3648 2096 11548 3683 2100 11549 3682 2103 11550 3685 2097 11551 3688 2088 11552 3657 2103 11553 3685 2088 11554 3657 2093 11555 3656 2101 11556 3687 2103 11557 3685 2102 11558 3686 2097 11559 3688 2103 11560 3685 2101 11561 3687 2097 11562 3688 2106 11563 3690 2088 11564 3657 2106 11565 3690 2105 11566 3691 2104 11567 3689 2106 11568 3690 2097 11569 3688 2105 11570 3691 2088 11571 3657 2106 11572 3690 2094 11573 3658 2096 11574 3683 2095 11575 3666 2109 11576 3692 2095 11577 3666 2096 11578 3683 2084 11579 3647 2107 11580 3694 2109 11581 3692 2108 11582 3693 2096 11583 3683 2109 11584 3692 2107 11585 3694 2121 11586 3698 2110 11587 3696 2120 11588 3697 2110 11589 3696 2121 11590 3698 2111 11591 3695 2122 11592 3700 2111 11593 3695 2121 11594 3698 2111 11595 3695 2122 11596 3700 2112 11597 3699 2122 11598 3700 2123 11599 3702 2113 11600 3701 2113 11601 3701 2112 11602 3699 2122 11603 3700 2124 11604 3704 2113 11605 3701 2123 11606 3702 2113 11607 3701 2124 11608 3704 2114 11609 3703 2124 11610 3707 2125 11611 3708 2115 11612 3705 2124 11613 3707 2115 11614 3705 2114 11615 3706 2126 11616 3710 2115 11617 3705 2125 11618 3708 2115 11619 3705 2126 11620 3710 2116 11621 3709 2126 11622 3710 2127 11623 3712 2117 11624 3711 2126 11625 3710 2117 11626 3711 2116 11627 3709 2127 11628 3712 2128 11629 3714 2118 11630 3713 2127 11631 3712 2118 11632 3713 2117 11633 3711 2128 11634 3714 2129 11635 3716 2119 11636 3715 2128 11637 3714 2119 11638 3715 2118 11639 3713 2120 11640 3697 2119 11641 3715 2129 11642 3716 2119 11643 3715 2120 11644 3697 2110 11645 3696 2120 11646 3697 2131 11647 3718 2121 11648 3698 2131 11649 3718 2120 11650 3697 2130 11651 3717 2132 11652 3719 2121 11653 3698 2131 11654 3718 2121 11655 3698 2132 11656 3719 2122 11657 3700 2132 11658 3719 2133 11659 3720 2123 11660 3702 2132 11661 3719 2123 11662 3702 2122 11663 3700 2133 11664 3720 2134 11665 3721 2124 11666 3704 2124 11667 3704 2123 11668 3702 2133 11669 3720 2124 11670 3707 2135 11671 3723 2125 11672 3708 2135 11673 3723 2124 11674 3707 2134 11675 3722 2136 11676 3724 2125 11677 3708 2135 11678 3723 2125 11679 3708 2136 11680 3724 2126 11681 3710 2136 11682 3724 2137 11683 3725 2127 11684 3712 2136 11685 3724 2127 11686 3712 2126 11687 3710 2128 11688 3714 2127 11689 3712 2137 11690 3725 2128 11691 3714 2137 11692 3725 2138 11693 3726 2138 11694 3726 2139 11695 3727 2129 11696 3716 2138 11697 3726 2129 11698 3716 2128 11699 3714 2130 11700 3717 2129 11701 3716 2139 11702 3727 2129 11703 3716 2130 11704 3717 2120 11705 3697 2130 11706 3717 2141 11707 3729 2131 11708 3718 2141 11709 3729 2130 11710 3717 2140 11711 3728 2131 11712 3718 2142 11713 3730 2132 11714 3719 2142 11715 3730 2131 11716 3718 2141 11717 3729 2142 11718 3730 2143 11719 3731 2133 11720 3720 2142 11721 3730 2133 11722 3720 2132 11723 3719 2143 11724 3731 2144 11725 3732 2134 11726 3721 2134 11727 3721 2133 11728 3720 2143 11729 3731 2134 11730 3722 2145 11731 3734 2135 11732 3723 2145 11733 3734 2134 11734 3722 2144 11735 3733 2146 11736 3735 2135 11737 3723 2145 11738 3734 2135 11739 3723 2146 11740 3735 2136 11741 3724 2146 11742 3735 2147 11743 3736 2137 11744 3725 2146 11745 3735 2137 11746 3725 2136 11747 3724 2138 11748 3726 2137 11749 3725 2147 11750 3736 2138 11751 3726 2147 11752 3736 2148 11753 3737 2148 11754 3737 2149 11755 3738 2139 11756 3727 2148 11757 3737 2139 11758 3727 2138 11759 3726 2140 11760 3728 2139 11761 3727 2149 11762 3738 2139 11763 3727 2140 11764 3728 2130 11765 3717 2140 11766 3728 2151 11767 3740 2141 11768 3729 2151 11769 3740 2140 11770 3728 2150 11771 3739 2152 11772 3741 2141 11773 3729 2151 11774 3740 2141 11775 3729 2152 11776 3741 2142 11777 3730 2152 11778 3741 2153 11779 3742 2143 11780 3731 2152 11781 3741 2143 11782 3731 2142 11783 3730 2153 11784 3742 2154 11785 3743 2144 11786 3732 2144 11787 3732 2143 11788 3731 2153 11789 3742 2144 11790 3733 2155 11791 3745 2145 11792 3734 2155 11793 3745 2144 11794 3733 2154 11795 3744 2156 11796 3746 2145 11797 3734 2155 11798 3745 2145 11799 3734 2156 11800 3746 2146 11801 3735 2156 11802 3746 2147 11803 3736 2146 11804 3735 2147 11805 3736 2156 11806 3746 2157 11807 3747 2148 11808 3737 2147 11809 3736 2157 11810 3747 2148 11811 3737 2157 11812 3747 2158 11813 3748 2158 11814 3748 2159 11815 3749 2149 11816 3738 2158 11817 3748 2149 11818 3738 2148 11819 3737 2150 11820 3739 2149 11821 3738 2159 11822 3749 2149 11823 3738 2150 11824 3739 2140 11825 3728 2150 11826 3739 2161 11827 3751 2151 11828 3740 2161 11829 3751 2150 11830 3739 2160 11831 3750 2151 11832 3740 2162 11833 3752 2152 11834 3741 2162 11835 3752 2151 11836 3740 2161 11837 3751 2153 11838 3742 2152 11839 3741 2162 11840 3752 2153 11841 3742 2162 11842 3752 2163 11843 3753 2154 11844 3743 2153 11845 3742 2163 11846 3753 2154 11847 3743 2163 11848 3753 2164 11849 3754 2154 11850 3744 2165 11851 3756 2155 11852 3745 2165 11853 3756 2154 11854 3744 2164 11855 3755 2155 11856 3745 2166 11857 3757 2156 11858 3746 2166 11859 3757 2155 11860 3745 2165 11861 3756 2166 11862 3757 2157 11863 3747 2156 11864 3746 2157 11865 3747 2166 11866 3757 2167 11867 3758 2167 11868 3758 2158 11869 3748 2157 11870 3747 2158 11871 3748 2167 11872 3758 2168 11873 3759 2158 11874 3748 2169 11875 3760 2159 11876 3749 2169 11877 3760 2158 11878 3748 2168 11879 3759 2150 11880 3739 2159 11881 3749 2169 11882 3760 2150 11883 3739 2169 11884 3760 2160 11885 3750 2161 11886 3751 2160 11887 3750 2170 11888 3761 2161 11889 3751 2170 11890 3761 2171 11891 3762 2162 11892 3752 2161 11893 3751 2171 11894 3762 2162 11895 3752 2171 11896 3762 2172 11897 3763 2162 11898 3752 2173 11899 3764 2163 11900 3753 2173 11901 3764 2162 11902 3752 2172 11903 3763 2164 11904 3754 2163 11905 3753 2173 11906 3764 2164 11907 3754 2173 11908 3764 2174 11909 3765 2164 11910 3755 2175 11911 3767 2165 11912 3756 2175 11913 3767 2164 11914 3755 2174 11915 3766 2175 11916 3767 2166 11917 3757 2165 11918 3756 2166 11919 3757 2175 11920 3767 2176 11921 3768 2166 11922 3757 2177 11923 3769 2167 11924 3758 2177 11925 3769 2166 11926 3757 2176 11927 3768 2167 11928 3758 2178 11929 3770 2168 11930 3759 2178 11931 3770 2167 11932 3758 2177 11933 3769 2168 11934 3759 2179 11935 3771 2169 11936 3760 2179 11937 3771 2168 11938 3759 2178 11939 3770 2160 11940 3750 2169 11941 3760 2179 11942 3771 2160 11943 3750 2179 11944 3771 2170 11945 3761 2171 11946 3762 2170 11947 3761 2180 11948 3772 2171 11949 3762 2180 11950 3772 2181 11951 3773 2181 11952 3773 2182 11953 3774 2172 11954 3763 2172 11955 3763 2171 11956 3762 2181 11957 3773 2183 11958 3775 2172 11959 3763 2182 11960 3774 2172 11961 3763 2183 11962 3775 2173 11963 3764 2173 11964 3764 2184 11965 3776 2174 11966 3765 2184 11967 3776 2173 11968 3764 2183 11969 3775 2184 11970 3777 2185 11971 3778 2175 11972 3767 2175 11973 3767 2174 11974 3766 2184 11975 3777 2185 11976 3778 2186 11977 3779 2176 11978 3768 2176 11979 3768 2175 11980 3767 2185 11981 3778 2176 11982 3768 2187 11983 3780 2177 11984 3769 2187 11985 3780 2176 11986 3768 2186 11987 3779 2177 11988 3769 2188 11989 3781 2178 11990 3770 2188 11991 3781 2177 11992 3769 2187 11993 3780 2189 11994 3782 2178 11995 3770 2188 11996 3781 2178 11997 3770 2189 11998 3782 2179 11999 3771 2170 12000 3761 2189 12001 3782 2180 12002 3772 2189 12003 3782 2170 12004 3761 2179 12005 3771 2181 12006 3773 2180 12007 3772 2190 12008 3783 2181 12009 3773 2190 12010 3783 2191 12011 3784 2191 12012 3784 2192 12013 3785 2182 12014 3774 2182 12015 3774 2181 12016 3773 2191 12017 3784 2193 12018 3786 2182 12019 3774 2192 12020 3785 2182 12021 3774 2193 12022 3786 2183 12023 3775 2183 12024 3775 2194 12025 3787 2184 12026 3776 2194 12027 3787 2183 12028 3775 2193 12029 3786 2194 12030 3788 2195 12031 3789 2185 12032 3778 2185 12033 3778 2184 12034 3777 2194 12035 3788 2195 12036 3789 2196 12037 3790 2186 12038 3779 2186 12039 3779 2185 12040 3778 2195 12041 3789 2186 12042 3779 2197 12043 3791 2187 12044 3780 2197 12045 3791 2186 12046 3779 2196 12047 3790 2187 12048 3780 2198 12049 3792 2188 12050 3781 2198 12051 3792 2187 12052 3780 2197 12053 3791 2199 12054 3793 2188 12055 3781 2198 12056 3792 2188 12057 3781 2199 12058 3793 2189 12059 3782 2180 12060 3772 2199 12061 3793 2190 12062 3783 2199 12063 3793 2180 12064 3772 2189 12065 3782 2191 12066 3784 2190 12067 3783 2200 12068 3794 2191 12069 3784 2200 12070 3794 2201 12071 3795 2192 12072 3785 2191 12073 3784 2201 12074 3795 2192 12075 3785 2201 12076 3795 2202 12077 3796 2192 12078 3785 2203 12079 3797 2193 12080 3786 2203 12081 3797 2192 12082 3785 2202 12083 3796 2193 12084 3786 2204 12085 3798 2194 12086 3787 2204 12087 3798 2193 12088 3786 2203 12089 3797 2204 12090 3799 2205 12091 3800 2195 12092 3789 2195 12093 3789 2194 12094 3788 2204 12095 3799 2196 12096 3790 2195 12097 3789 2205 12098 3800 2196 12099 3790 2205 12100 3800 2206 12101 3801 2196 12102 3790 2207 12103 3802 2197 12104 3791 2207 12105 3802 2196 12106 3790 2206 12107 3801 2197 12108 3791 2208 12109 3803 2198 12110 3792 2208 12111 3803 2197 12112 3791 2207 12113 3802 2209 12114 3804 2198 12115 3792 2208 12116 3803 2198 12117 3792 2209 12118 3804 2199 12119 3793 2190 12120 3783 2209 12121 3804 2200 12122 3794 2209 12123 3804 2190 12124 3783 2199 12125 3793 2110 12126 3805 2111 12127 3806 2201 12128 3795 2201 12129 3795 2200 12130 3794 2110 12131 3805 2111 12132 3806 2112 12133 3807 2202 12134 3796 2202 12135 3796 2201 12136 3795 2111 12137 3806 2113 12138 3808 2202 12139 3796 2112 12140 3807 2202 12141 3796 2113 12142 3808 2203 12143 3797 2114 12144 3809 2203 12145 3797 2113 12146 3808 2203 12147 3797 2114 12148 3809 2204 12149 3798 2114 12150 3810 2115 12151 3811 2205 12152 3800 2114 12153 3810 2205 12154 3800 2204 12155 3799 2115 12156 3811 2116 12157 3812 2206 12158 3801 2115 12159 3811 2206 12160 3801 2205 12161 3800 2117 12162 3813 2206 12163 3801 2116 12164 3812 2206 12165 3801 2117 12166 3813 2207 12167 3802 2118 12168 3814 2207 12169 3802 2117 12170 3813 2207 12171 3802 2118 12172 3814 2208 12173 3803 2118 12174 3814 2119 12175 3815 2209 12176 3804 2118 12177 3814 2209 12178 3804 2208 12179 3803 2110 12180 3805 2209 12181 3804 2119 12182 3815 2209 12183 3804 2110 12184 3805 2200 12185 3794 2210 12186 3822 1294 12187 1987 2212 12188 3825 1295 12189 1986 1294 12190 1987 2210 12191 3822 2211 12192 3824 2212 12193 3825 2213 12194 3827 2212 12195 3825 2211 12196 3824 2210 12197 3822 1238 12198 1853 2212 12199 3825 1294 12200 1987 1238 12201 1853 1226 12202 1882 2212 12203 3825 1226 12204 1882 2213 12205 3827 2212 12206 3825 2214 12207 3828 1383 12208 2171 1346 12209 2097 2214 12210 3828 1324 12211 2098 2215 12212 3829 1324 12213 2098 2214 12214 3828 1346 12215 2097 1382 12216 2170 2214 12217 3828 2216 12218 3831 2214 12219 3828 1382 12220 2170 1383 12221 2171 2216 12222 3831 2215 12223 3829 2217 12224 3832 2215 12225 3829 2216 12226 3831 2214 12227 3828 2218 12228 3834 1387 12229 2176 1343 12230 2083 1327 12231 2084 2218 12232 3834 1343 12233 2083 2218 12234 3834 1327 12235 2084 2219 12236 3836 2218 12237 3834 1386 12238 2175 1387 12239 2176 1386 12240 2175 2218 12241 3834 2220 12242 3837 2219 12243 3836 2220 12244 3837 2218 12245 3834 2220 12246 3837 2219 12247 3836 2221 12248 3839 1239 12249 1870 2222 12250 3840 1298 12251 1991 2222 12252 3840 1217 12253 1871 2223 12254 3841 1217 12255 1871 2222 12256 3840 1239 12257 1870 1299 12258 1992 2222 12259 3840 2224 12260 3843 2222 12261 3840 1299 12262 1992 1298 12263 1991 2224 12264 3843 2223 12265 3841 2225 12266 3844 2223 12267 3841 2224 12268 3843 2222 12269 3840</p> + </triangles> + </mesh> + </geometry> + </library_geometries> + <library_animations> + <animation id="MineCartEngine-anim" name="MineCartEngine"> + <animation> + <source id="MineCartEngine-Matrix-animation-input"> + <float_array id="MineCartEngine-Matrix-animation-input-array" count="101"> + +0.000000 0.033333 0.066667 0.100000 0.133333 0.166667 0.200000 0.233333 0.266667 0.300000 0.333333 0.366667 0.400000 0.433333 0.466667 0.500000 +0.533333 0.566667 0.600000 0.633333 0.666667 0.700000 0.733333 0.766667 0.800000 0.833333 0.866667 0.900000 0.933333 0.966667 1.000000 1.033333 +1.066667 1.100000 1.133333 1.166667 1.200000 1.233333 1.266667 1.300000 1.333333 1.366667 1.400000 1.433333 1.466667 1.500000 1.533333 1.566667 +1.600000 1.633333 1.666667 1.700000 1.733333 1.766667 1.800000 1.833333 1.866667 1.900000 1.933333 1.966667 2.000000 2.033333 2.066667 2.100000 +2.133333 2.166667 2.200000 2.233333 2.266667 2.300000 2.333333 2.366667 2.400000 2.433333 2.466667 2.500000 2.533333 2.566667 2.600000 2.633333 +2.666667 2.700000 2.733333 2.766667 2.800000 2.833333 2.866667 2.900000 2.933333 2.966667 3.000000 3.033333 3.066667 3.100000 3.133333 3.166667 +3.200000 3.233333 3.266667 3.300000 3.333333</float_array> + <technique_common> + <accessor source="#MineCartEngine-Matrix-animation-input-array" count="101"> + <param name="TIME" type="float"/> + </accessor> + </technique_common> + </source> + <source id="MineCartEngine-Matrix-animation-output-transform"> + <float_array id="MineCartEngine-Matrix-animation-output-transform-array" count="1616"> + +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000</float_array> + <technique_common> + <accessor source="#MineCartEngine-Matrix-animation-output-transform-array" count="101" stride="16"> + <param type="float4x4"/> + </accessor> + </technique_common> + </source> + <source id="MineCartEngine-Interpolations"> + <Name_array id="MineCartEngine-Interpolations-array" count="101"> + LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR +LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR +LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR +LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR +LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR +LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR +LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR +LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR +LINEAR LINEAR LINEAR LINEAR LINEAR LINEAR</Name_array> + <technique_common> + <accessor source="#MineCartEngine-Interpolations-array" count="101"> + <param type="name"/> + </accessor> + </technique_common> + </source> + <sampler id="MineCartEngine-Matrix-animation-transform"> + <input semantic="INPUT" source="#MineCartEngine-Matrix-animation-input"/> + <input semantic="OUTPUT" source="#MineCartEngine-Matrix-animation-output-transform"/> + <input semantic="INTERPOLATION" source="#MineCartEngine-Interpolations"/> + </sampler> + <channel source="#MineCartEngine-Matrix-animation-transform" target="MineCartEngine/matrix"/> + </animation> + </animation> + </library_animations> + <library_visual_scenes> + <visual_scene id="minecartengine" name="minecartengine"> + <node name="MineCartEngine" id="MineCartEngine" sid="MineCartEngine"> + <matrix sid="matrix">1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000</matrix> + <instance_geometry url="#MineCartEngine-lib"> + <bind_material> + <technique_common> + <instance_material symbol="MineCartEngine_ncl1_1" target="#MineCartEngine_ncl1_1"/> + </technique_common> + </bind_material> + </instance_geometry> + <extra> + <technique profile="FCOLLADA"> + <visibility>1.000000</visibility> + </technique> + </extra> + </node> + <extra> + <technique profile="MAX3D"> + <frame_rate>30.000000</frame_rate> + </technique> + <technique profile="FCOLLADA"> + <start_time>0.000000</start_time> + <end_time>3.333333</end_time> + </technique> + </extra> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#minecartengine"/> + </scene> +</COLLADA> diff --git a/test_world/model.config b/test_world/model.config new file mode 100644 index 0000000..7e19b2b --- /dev/null +++ b/test_world/model.config @@ -0,0 +1,15 @@ +<?xml version="1.0"?> +<model> + <name>Mine Cart Engine</name> + <version>1.0</version> + <sdf version="1.6">model.sdf</sdf> + + <author> + <name>Cole Biesemeyer</name> + <email>cole@openrobotics.org</email> + </author> + + <description> + A mine cart engine. + </description> +</model> diff --git a/test_world/model.sdf b/test_world/model.sdf new file mode 100644 index 0000000..2896fc3 --- /dev/null +++ b/test_world/model.sdf @@ -0,0 +1,44 @@ +<?xml version="1.0"?> +<sdf version="1.6"> + <model name="minecartengine"> + <static>true</static> + <link name="base_link"> + <collision name="collision"> + <geometry> + <mesh> + <uri>meshes/minecartengine.dae</uri> + <scale>1.0 1.0 1.0</scale> + </mesh> + </geometry> + </collision> + <visual name= "MineCartEngine_visual"> + <geometry> + <mesh> + <uri>meshes/minecartengine.dae</uri> + <submesh> + <name>MineCartEngine</name> + <center>false</center> + </submesh> + </mesh> + </geometry> + <material> + <diffuse>1.0 1.0 1.0</diffuse> + <specular>1.0 1.0 1.0</specular> + <pbr> + <metal> + <albedo_map>materials/textures/MineCartEngine_Albedo.png</albedo_map> + <metalness_map>materials/textures/MineCartEngine_Metalness.png</metalness_map> + <roughness_map>materials/textures/MineCartEngine_Roughness.png</roughness_map> + </metal> + </pbr> + <!-- fallback to script if no PBR support--> + <script> + <uri>materials/scripts/</uri> + <uri>materials/textures/</uri> + <name>UrbanTile/MineCartEngine_Diffuse</name> + </script> + </material> + </visual> + </link> + </model> +</sdf> diff --git a/test_world/test_world.sdf b/test_world/test_world.sdf new file mode 100644 index 0000000..0c85c6b --- /dev/null +++ b/test_world/test_world.sdf @@ -0,0 +1,70 @@ +<sdf version='1.9'> + <world name='default'> + <gravity>0 0 -9.8</gravity> + <magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field> + <atmosphere type='adiabatic'/> + <physics type='ode'> + <max_step_size>0.001</max_step_size> + <real_time_factor>1</real_time_factor> + <real_time_update_rate>1000</real_time_update_rate> + </physics> + <scene> + <ambient>0.4 0.4 0.4 1</ambient> + <background>0.7 0.7 0.7 1</background> + <shadows>true</shadows> + </scene> + <model name='cylinder'> + <pose>-0.374767 0.30927 0.5 0 -0 0</pose> + <link name='cylinder_link'> + <inertial> + <inertia> + <ixx>0.14580000000000001</ixx> + <ixy>0</ixy> + <ixz>0</ixz> + <iyy>0.14580000000000001</iyy> + <iyz>0</iyz> + <izz>0.125</izz> + </inertia> + <mass>1</mass> + <pose>0 0 0 0 -0 0</pose> + </inertial> + <collision name='cylinder_collision'> + <geometry> + <cylinder> + <radius>0.5</radius> + <length>1</length> + </cylinder> + </geometry> + <surface> + <friction> + <ode/> + </friction> + <bounce/> + <contact/> + </surface> + </collision> + <visual name='cylinder_visual'> + <geometry> + <cylinder> + <radius>0.5</radius> + <length>1</length> + </cylinder> + </geometry> + <material> + <ambient>0.3 0.3 0.3 1</ambient> + <diffuse>0.7 0.7 0.7 1</diffuse> + <specular>1 1 1 1</specular> + </material> + </visual> + <pose>0 0 0 0 -0 0</pose> + <enable_wind>false</enable_wind> + </link> + <static>false</static> + <self_collide>false</self_collide> + </model> + <plugin + filename="RGLGazeboPlugin" + name="rgl::RGLGazeboPlugin"> + </plugin> + </world> +</sdf>